15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_ROUTE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_ROUTE_ACTION_HPP_
20 #include "nav2_msgs/action/compute_route.hpp"
21 #include "nav_msgs/msg/path.h"
22 #include "nav2_behavior_tree/bt_action_node.hpp"
24 namespace nav2_behavior_tree
32 using Action = nav2_msgs::action::ComputeRoute;
33 using ActionResult = Action::Result;
43 const std::string & xml_tag_name,
44 const std::string & action_name,
45 const BT::NodeConfiguration & conf);
91 BT::InputPort<unsigned int>(
"start_id",
"ID of the start node"),
92 BT::InputPort<unsigned int>(
"goal_id",
"ID of the goal node"),
93 BT::InputPort<geometry_msgs::msg::PoseStamped>(
95 "Start pose of the path if overriding current robot pose and using poses over IDs"),
96 BT::InputPort<geometry_msgs::msg::PoseStamped>(
97 "goal",
"Goal pose of the path if using poses over IDs"),
100 "Whether to use the start pose or the robot's current pose"),
102 "use_poses",
false,
"Whether to use poses or IDs for start and goal"),
103 BT::OutputPort<ActionResult::_route_type>(
104 "route",
"The route computed by ComputeRoute node"),
105 BT::OutputPort<builtin_interfaces::msg::Duration>(
"planning_time",
106 "Time taken to compute route"),
107 BT::OutputPort<nav_msgs::msg::Path>(
"path",
"Path created by ComputeRoute node"),
108 BT::OutputPort<ActionResult::_error_code_type>(
109 "error_code_id",
"The compute route error code"),
110 BT::OutputPort<std::string>(
111 "error_msg",
"The compute route error msg"),
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::ComputeRoute.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
ComputeRouteAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputeRoute.
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
void on_tick() override
Function to perform some user-defined operation on tick.
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
static BT::PortsList providedPorts()
Creates list of BT ports.
void resetPorts()
Reset output port values on failure.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.