Skip to content

Commit

Permalink
fix: wrong input type in navigate_to_pose_action.hpp and navigate_to_… (
Browse files Browse the repository at this point in the history
#2994)

* fix: wrong input type in navigate_to_pose_action.hpp and navigate_to_pose_action.hpp

* Update navigate_through_poses_action.hpp

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
  • Loading branch information
shoufei403 and SteveMacenski committed Aug 24, 2022
1 parent 71f9a62 commit dcb426c
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
return providedBasicPorts(
{
BT::InputPort<geometry_msgs::msg::PoseStamped>("goals", "Destinations to plan through"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("behavior_tree", "Behavior tree to run"),
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
});
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class NavigateToPoseAction : public BtActionNode<nav2_msgs::action::NavigateToPo
return providedBasicPorts(
{
BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
BT::InputPort<geometry_msgs::msg::PoseStamped>("behavior_tree", "Behavior tree to run"),
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
});
}
};
Expand Down

0 comments on commit dcb426c

Please sign in to comment.