18 #include "nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp"
20 namespace nav2_behavior_tree
24 const std::string & xml_tag_name,
25 const std::string & action_name,
26 const BT::NodeConfiguration & conf)
33 getInput(
"goal", goal_.goal);
34 getInput(
"planner_id", goal_.planner_id);
38 goal_.use_start =
false;
39 if (getInput(
"use_start", goal_.use_start)) {
40 if (goal_.use_start && !getInput(
"start", goal_.start)) {
42 goal_.use_start =
false;
45 "use_start is set to true but no start pose was provided, falling back to default "
46 "behavior, i.e. using the current robot pose");
51 if (getInput(
"start", goal_.start)) {
52 goal_.use_start =
true;
59 setOutput(
"path", result_.result->path);
61 setOutput(
"error_code_id", ActionResult::NONE);
62 setOutput(
"error_msg",
"");
63 return BT::NodeStatus::SUCCESS;
68 nav_msgs::msg::Path empty_path;
69 setOutput(
"path", empty_path);
70 setOutput(
"error_code_id", result_.result->error_code);
71 setOutput(
"error_msg", result_.result->error_msg);
72 return BT::NodeStatus::FAILURE;
77 nav_msgs::msg::Path empty_path;
78 setOutput(
"path", empty_path);
80 setOutput(
"error_code_id", ActionResult::NONE);
81 setOutput(
"error_msg",
"");
82 return BT::NodeStatus::SUCCESS;
87 setOutput(
"error_code_id", ActionResult::TIMEOUT);
88 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
93 nav_msgs::msg::Path empty_path;
94 setOutput(
"path", empty_path);
102 #include "behaviortree_cpp/bt_factory.h"
103 BT_REGISTER_NODES(factory)
105 BT::NodeBuilder builder =
106 [](
const std::string & name,
const BT::NodeConfiguration & config)
108 return std::make_unique<nav2_behavior_tree::ComputePathToPoseAction>(
109 name,
"compute_path_to_pose", config);
113 "ComputePathToPose", builder);
Abstract class representing an action based BT node.
void halt() override
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 ...
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.
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.