Skip to content

Commit

Permalink
fix
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Jan 10, 2025
1 parent c0f1e8b commit 1d55e6c
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

#include <memory>
#include <string>
#include <vector>

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped_array.hpp"
Expand Down Expand Up @@ -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);

Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 "
Expand Down

0 comments on commit 1d55e6c

Please sign in to comment.