Skip to content

Commit 51f54eb

Browse files
committed
fix test
Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com>
1 parent 4d2b402 commit 51f54eb

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

‎nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,18 +36,18 @@ BT::NodeStatus GoalUpdatedController::tick()
3636
// Reset since we're starting a new iteration of
3737
// the goal updated controller (moving from IDLE to RUNNING)
3838

39-
BT::getInputOrBlackboard("goals", goals_);
40-
BT::getInputOrBlackboard("goal", goal_);
39+
goals_ = config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals");
40+
goal_ = config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal");
4141

4242
goal_was_updated_ = true;
4343
}
4444

4545
setStatus(BT::NodeStatus::RUNNING);
4646

4747
std::vector<geometry_msgs::msg::PoseStamped> current_goals;
48-
BT::getInputOrBlackboard("goals", current_goals);
48+
current_goals = config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals");
4949
geometry_msgs::msg::PoseStamped current_goal;
50-
BT::getInputOrBlackboard("goal", current_goal);
50+
current_goal = config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal");
5151

5252
if (goal_ != current_goal || goals_ != current_goals) {
5353
goal_ = current_goal;

0 commit comments

Comments
 (0)