15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__DRIVE_ON_HEADING_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__DRIVE_ON_HEADING_ACTION_HPP_
20 #include "nav2_behavior_tree/bt_action_node.hpp"
21 #include "nav2_msgs/action/drive_on_heading.hpp"
22 #include "nav2_ros_common/lifecycle_node.hpp"
24 namespace nav2_behavior_tree
34 using Action = nav2_msgs::action::DriveOnHeading;
35 using ActionResult = Action::Result;
45 const std::string & xml_tag_name,
46 const std::string & action_name,
47 const BT::NodeConfiguration & conf);
62 BT::InputPort<double>(
"dist_to_travel", 0.15,
"Distance to travel"),
63 BT::InputPort<double>(
"speed", 0.025,
"Speed at which to travel"),
64 BT::InputPort<double>(
"time_allowance", 10.0,
"Allowed time for driving on heading"),
65 BT::InputPort<bool>(
"disable_collision_checks",
false,
"Disable collision checking"),
66 BT::OutputPort<Action::Result::_error_code_type>(
67 "error_code_id",
"The drive on heading behavior server error code"),
68 BT::OutputPort<std::string>(
69 "error_msg",
"The drive on heading behavior server 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::DriveOnHeading.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion 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...
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
DriveOnHeadingAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::DriveOnHeadingAction.
void on_tick() override
Function to perform some user-defined operation on tick.
void initialize()
Function to read parameters and initialize class variables.
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.