diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp index d5c16ee61c0..19b0a8a34b6 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp @@ -19,7 +19,6 @@ #include #include -#include #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose_stamped_array.hpp" @@ -78,7 +77,7 @@ class GoalUpdater : public BT::DecoratorNode /** * @brief Callback function for goals update topic - * @param msg Shared pointer to vector of geometry_msgs::msg::PoseStamped message + * @param msg Shared pointer to geometry_msgs::msg::PoseStampedArray message */ void callback_updated_goals(const geometry_msgs::msg::PoseStampedArray::SharedPtr msg); diff --git a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp index ad8bd8c970a..2fcd19a567b 100644 --- a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp +++ b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp @@ -99,7 +99,7 @@ inline BT::NodeStatus GoalUpdater::tick() auto last_goals_received_time = rclcpp::Time(last_goals_received_.header.stamp); auto goals_time = rclcpp::Time(goals.header.stamp); if (last_goals_received_time > goals_time) { - setOutput("output_goals", last_goals_received_.poses); + setOutput("output_goals", last_goals_received_); } else { RCLCPP_WARN( node_->get_logger(), "The timestamp of the received goals (%f) is older than the "