Skip to content

Commit

Permalink
use PoseStampedArray
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Jan 7, 2025
1 parent 3247145 commit bc1d94c
Showing 1 changed file with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ namespace nav2_behavior_tree
class GoalUpdater : public BT::DecoratorNode
{
public:
typedef std::vector<geometry_msgs::msg::PoseStamped> Goals;
/**
* @brief A constructor for nav2_behavior_tree::GoalUpdater
* @param xml_tag_name Name for the XML tag for this node
Expand All @@ -56,10 +55,10 @@ class GoalUpdater : public BT::DecoratorNode
{
return {
BT::InputPort<geometry_msgs::msg::PoseStamped>("input_goal", "Original Goal"),
BT::InputPort<Goals>("input_goals", "Original Goals"),
BT::InputPort<geometry_msgs::msg::PoseStampedArray>("input_goals", "Original Goals"),
BT::OutputPort<geometry_msgs::msg::PoseStamped>("output_goal",
"Received Goal by subscription"),
BT::OutputPort<Goals>("output_goals", "Received Goals by subscription")
BT::OutputPort<geometry_msgs::msg::PoseStampedArray>("output_goals", "Received Goals by subscription")
};
}

Expand Down

0 comments on commit bc1d94c

Please sign in to comment.