Skip to content

Commit 1d55e6c

Browse files
committed
fix
Signed-off-by: Tony Najjar <[email protected]>
1 parent c0f1e8b commit 1d55e6c

File tree

2 files changed

+2
-3
lines changed

2 files changed

+2
-3
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@
1919

2020
#include <memory>
2121
#include <string>
22-
#include <vector>
2322

2423
#include "geometry_msgs/msg/pose_stamped.hpp"
2524
#include "geometry_msgs/msg/pose_stamped_array.hpp"
@@ -78,7 +77,7 @@ class GoalUpdater : public BT::DecoratorNode
7877

7978
/**
8079
* @brief Callback function for goals update topic
81-
* @param msg Shared pointer to vector of geometry_msgs::msg::PoseStamped message
80+
* @param msg Shared pointer to geometry_msgs::msg::PoseStampedArray message
8281
*/
8382
void callback_updated_goals(const geometry_msgs::msg::PoseStampedArray::SharedPtr msg);
8483

nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ inline BT::NodeStatus GoalUpdater::tick()
9999
auto last_goals_received_time = rclcpp::Time(last_goals_received_.header.stamp);
100100
auto goals_time = rclcpp::Time(goals.header.stamp);
101101
if (last_goals_received_time > goals_time) {
102-
setOutput("output_goals", last_goals_received_.poses);
102+
setOutput("output_goals", last_goals_received_);
103103
} else {
104104
RCLCPP_WARN(
105105
node_->get_logger(), "The timestamp of the received goals (%f) is older than the "

0 commit comments

Comments
 (0)