19 #include "nav2_behavior_tree/plugins/action/smooth_path_action.hpp"
21 namespace nav2_behavior_tree
25 const std::string & xml_tag_name,
26 const std::string & action_name,
27 const BT::NodeConfiguration & conf)
28 :
BtActionNode<nav2_msgs::action::SmoothPath>(xml_tag_name, action_name, conf)
34 getInput(
"unsmoothed_path", goal_.path);
35 getInput(
"smoother_id", goal_.smoother_id);
36 double max_smoothing_duration;
37 getInput(
"max_smoothing_duration", max_smoothing_duration);
38 goal_.max_smoothing_duration = rclcpp::Duration::from_seconds(max_smoothing_duration);
39 getInput(
"check_for_collisions", goal_.check_for_collisions);
44 setOutput(
"smoothed_path", result_.result->path);
45 setOutput(
"smoothing_duration", rclcpp::Duration(result_.result->smoothing_duration).seconds());
46 setOutput(
"was_completed", result_.result->was_completed);
48 setOutput(
"error_code_id", ActionResult::NONE);
49 setOutput(
"error_msg",
"");
50 return BT::NodeStatus::SUCCESS;
55 setOutput(
"error_code_id", result_.result->error_code);
56 setOutput(
"error_msg", result_.result->error_msg);
57 return BT::NodeStatus::FAILURE;
63 setOutput(
"error_code_id", ActionResult::NONE);
64 setOutput(
"error_msg",
"");
65 return BT::NodeStatus::SUCCESS;
70 setOutput(
"error_code_id", ActionResult::TIMEOUT);
71 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
76 #include "behaviortree_cpp/bt_factory.h"
77 BT_REGISTER_NODES(factory)
79 BT::NodeBuilder builder =
80 [](
const std::string & name,
const BT::NodeConfiguration & config)
82 return std::make_unique<nav2_behavior_tree::SmoothPathAction>(
83 name,
"smooth_path", config);
87 "SmoothPath", builder);
Abstract class representing an action based BT node.
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.
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.