From 51f54ebb9bc8af4cab21d46f99cb37e326fd4a3a Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Tue, 3 Sep 2024 18:03:26 +0000 Subject: [PATCH] fix test Signed-off-by: Tony Najjar --- .../plugins/decorator/goal_updated_controller.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp b/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp index b2f235dbd1..17fcc34249 100644 --- a/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp @@ -36,8 +36,8 @@ BT::NodeStatus GoalUpdatedController::tick() // Reset since we're starting a new iteration of // the goal updated controller (moving from IDLE to RUNNING) - BT::getInputOrBlackboard("goals", goals_); - BT::getInputOrBlackboard("goal", goal_); + goals_ = config().blackboard->get>("goals"); + goal_ = config().blackboard->get("goal"); goal_was_updated_ = true; } @@ -45,9 +45,9 @@ BT::NodeStatus GoalUpdatedController::tick() setStatus(BT::NodeStatus::RUNNING); std::vector current_goals; - BT::getInputOrBlackboard("goals", current_goals); + current_goals = config().blackboard->get>("goals"); geometry_msgs::msg::PoseStamped current_goal; - BT::getInputOrBlackboard("goal", current_goal); + current_goal = config().blackboard->get("goal"); if (goal_ != current_goal || goals_ != current_goals) { goal_ = current_goal;