19 #include "nav2_behavior_tree/plugins/action/compute_path_through_poses_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::ComputePathThroughPoses>(xml_tag_name, action_name, conf)
34 getInput(
"goals", goal_.goals);
35 getInput(
"planner_id", goal_.planner_id);
36 if (getInput(
"start", goal_.start)) {
37 goal_.use_start =
true;
43 setOutput(
"path", result_.result->path);
45 setOutput(
"error_code_id", ActionResult::NONE);
46 setOutput(
"error_msg",
"");
47 return BT::NodeStatus::SUCCESS;
52 nav_msgs::msg::Path empty_path;
53 setOutput(
"path", empty_path);
54 setOutput(
"error_code_id", result_.result->error_code);
55 setOutput(
"error_msg", result_.result->error_msg);
56 return BT::NodeStatus::FAILURE;
61 nav_msgs::msg::Path empty_path;
62 setOutput(
"path", empty_path);
64 setOutput(
"error_code_id", ActionResult::NONE);
65 setOutput(
"error_msg",
"");
66 return BT::NodeStatus::SUCCESS;
71 setOutput(
"error_code_id", ActionResult::TIMEOUT);
72 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
77 nav_msgs::msg::Path empty_path;
78 setOutput(
"path", empty_path);
86 #include "behaviortree_cpp/bt_factory.h"
87 BT_REGISTER_NODES(factory)
89 BT::NodeBuilder builder =
90 [](
const std::string & name,
const BT::NodeConfiguration & config)
92 return std::make_unique<nav2_behavior_tree::ComputePathThroughPosesAction>(
93 name,
"compute_path_through_poses", config);
97 "ComputePathThroughPoses", 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::ComputePathThroughPoses.
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.
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_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.
ComputePathThroughPosesAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputePathThroughPosesAction.