16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SMOOTH_PATH_ACTION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SMOOTH_PATH_ACTION_HPP_
21 #include "nav2_msgs/action/smooth_path.hpp"
22 #include "nav_msgs/msg/path.h"
23 #include "nav2_behavior_tree/bt_action_node.hpp"
25 namespace nav2_behavior_tree
33 using Action = nav2_msgs::action::SmoothPath;
34 using ActionResult = Action::Result;
44 const std::string & xml_tag_name,
45 const std::string & action_name,
46 const BT::NodeConfiguration & conf);
81 BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
85 BT::InputPort<nav_msgs::msg::Path>(
"unsmoothed_path",
"Path to be smoothed"),
86 BT::InputPort<double>(
"max_smoothing_duration", 3.0,
"Maximum smoothing duration"),
88 "check_for_collisions",
false,
89 "If true collision check will be performed after smoothing"),
90 BT::InputPort<std::string>(
"smoother_id",
""),
91 BT::OutputPort<nav_msgs::msg::Path>(
93 "Path smoothed by SmootherServer node"),
94 BT::OutputPort<double>(
"smoothing_duration",
"Time taken to smooth path"),
96 "was_completed",
"True if smoothing was not interrupted by time limit"),
97 BT::OutputPort<ActionResult::_error_code_type>(
98 "error_code_id",
"The smooth path error code"),
99 BT::OutputPort<std::string>(
100 "error_msg",
"The smooth path 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::SmoothPath.
SmoothPathAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SmoothPathAction.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation 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 on_tick() override
Function to perform some user-defined operation on tick.