diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp index f87435995c5..fc95daaf439 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp @@ -61,6 +61,11 @@ class ComputePathToPoseAction : public BtActionNodeget>("goals", goals_); config().blackboard->get("goal", goal_); - return BT::NodeStatus::FAILURE; + return BT::NodeStatus::SUCCESS; } std::vector current_goals; diff --git a/nav2_behavior_tree/test/plugins/condition/test_globally_updated_goal.cpp b/nav2_behavior_tree/test/plugins/condition/test_globally_updated_goal.cpp index d41a6d424cc..2e6810f5102 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_globally_updated_goal.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_globally_updated_goal.cpp @@ -49,7 +49,7 @@ TEST_F(GloballyUpdatedGoalConditionTestFixture, test_behavior) config_->blackboard->set("goal", goal); EXPECT_EQ(bt_node_->status(), BT::NodeStatus::IDLE); - EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::FAILURE); + EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); goal.pose.position.x = 1.0; config_->blackboard->set("goal", goal); diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp index c6e0e484ad7..0fbe47501a8 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp @@ -15,6 +15,10 @@ #ifndef NAV2_COLLISION_MONITOR__RANGE_HPP_ #define NAV2_COLLISION_MONITOR__RANGE_HPP_ +#include +#include +#include + #include "sensor_msgs/msg/range.hpp" #include "nav2_collision_monitor/source.hpp"