15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_ACTION_HPP_
20 #include "nav2_msgs/action/compute_path_to_pose.hpp"
21 #include "nav_msgs/msg/path.hpp"
22 #include "nav2_behavior_tree/bt_action_node.hpp"
23 #include "nav2_ros_common/lifecycle_node.hpp"
25 namespace nav2_behavior_tree
35 using Action = nav2_msgs::action::ComputePathToPose;
36 using ActionResult = Action::Result;
46 const std::string & xml_tag_name,
47 const std::string & action_name,
48 const BT::NodeConfiguration & conf);
88 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
89 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
93 BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal",
"Destination to plan to"),
94 BT::InputPort<geometry_msgs::msg::PoseStamped>(
96 "Used as the planner start pose instead of the current robot pose, if use_start is"
97 " not false (i.e. not provided or set to true)"),
99 "use_start",
"For using or not using (i.e. ignoring) the provided start pose"),
100 BT::InputPort<std::string>(
102 "Mapped name to the planner plugin type to use"),
103 BT::OutputPort<nav_msgs::msg::Path>(
"path",
"Path created by ComputePathToPose node"),
104 BT::OutputPort<ActionResult::_error_code_type>(
105 "error_code_id",
"The compute path to pose error code"),
106 BT::OutputPort<std::string>(
107 "error_msg",
"The compute path to pose 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::ComputePathToPose.
void on_tick() override
Function to perform some user-defined operation on tick.
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
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.
ComputePathToPoseAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputePathToPoseAction.
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.