15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
21 #include "nav2_msgs/action/compute_and_track_route.hpp"
22 #include "nav2_behavior_tree/bt_action_node.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
25 namespace nav2_behavior_tree
33 using Action = nav2_msgs::action::ComputeAndTrackRoute;
34 using ActionResult = Action::Result;
44 const std::string & xml_tag_name,
45 const std::string & action_name,
46 const BT::NodeConfiguration & conf);
74 std::shared_ptr<const Action::Feedback> feedback)
override;
89 BT::InputPort<unsigned int>(
"start_id",
"ID of the start node"),
90 BT::InputPort<unsigned int>(
"goal_id",
"ID of the goal node"),
91 BT::InputPort<geometry_msgs::msg::PoseStamped>(
93 "Start pose of the path if overriding current robot pose and using poses over IDs"),
94 BT::InputPort<geometry_msgs::msg::PoseStamped>(
95 "goal",
"Goal pose of the path if using poses over IDs"),
98 "Whether to use the start pose or the robot's current pose"),
100 "use_poses",
false,
"Whether to use poses or IDs for start and goal"),
101 BT::OutputPort<builtin_interfaces::msg::Duration>(
102 "execution_duration",
103 "Time taken to compute and track route"),
104 BT::OutputPort<uint16_t>(
106 "ID of the previous node"),
107 BT::OutputPort<uint16_t>(
109 "ID of the next node"),
110 BT::OutputPort<uint16_t>(
112 "ID of current edge"),
113 BT::OutputPort<nav2_msgs::msg::Route>(
115 "List of RouteNodes to go from start to end"),
116 BT::OutputPort<nav_msgs::msg::Path>(
118 "Path created by ComputeAndTrackRoute node"),
119 BT::OutputPort<bool>(
121 "Whether the plan has rerouted"),
126 Action::Feedback feedback_;
Abstract class representing an action based BT node.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call pro...
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::ComputeAndTrackRoute.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
ComputeAndTrackRouteAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputeAndTrackRouteAction.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
void on_wait_for_result(std::shared_ptr< const Action::Feedback > feedback) override
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been...
void on_tick() override
Function to perform some user-defined operation on tick.
void resetFeedbackAndOutputPorts()
Function to set all feedbacks and output ports to be null values.