15 #ifndef OPENNAV_DOCKING_BT__DOCK_ROBOT_HPP_
16 #define OPENNAV_DOCKING_BT__DOCK_ROBOT_HPP_
22 #include "nav2_msgs/action/dock_robot.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "nav2_behavior_tree/bt_action_node.hpp"
26 namespace opennav_docking_bt
34 nav2_msgs::action::DockRobot>
36 using Action = nav2_msgs::action::DockRobot;
37 using ActionResult = Action::Result;
47 const std::string & xml_tag_name,
48 const std::string & action_name,
49 const BT::NodeConfiguration & conf);
92 "Whether to use the dock's ID or dock pose fields"),
93 BT::InputPort<std::string>(
"dock_id",
"Dock ID or name to use"),
94 BT::InputPort<geometry_msgs::msg::PoseStamped>(
95 "dock_pose",
"The dock pose, if not using dock id"),
96 BT::InputPort<std::string>(
"dock_type",
"The dock plugin type, if using dock pose"),
98 "max_staging_time", 1000.0,
"Maximum time to navigate to the staging pose"),
100 "navigate_to_staging_pose",
true,
"Whether to autonomously navigate to staging pose"),
102 BT::OutputPort<ActionResult::_success_type>(
103 "success",
"If the action was successful"),
104 BT::OutputPort<ActionResult::_error_code_type>(
105 "error_code_id",
"Error code"),
106 BT::OutputPort<std::string>(
107 "error_msg",
"Error message"),
108 BT::OutputPort<ActionResult::_num_retries_type>(
109 "num_retries",
"The number of retries executed"),
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...
nav2_behavior_tree::BtActionNode class that wraps opnav2_msgsennav_docking_msgs/DockRobot
void on_tick() override
Function to perform some user-defined operation on tick.
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
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.
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
DockRobotAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for opennav_docking_bt::DockRobotAction.