18 #include "nav2_behavior_tree/plugins/action/compute_route_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 bool use_poses =
false, use_start =
false;
34 getInput(
"use_poses", use_poses);
36 goal_.use_poses =
true;
37 getInput(
"goal", goal_.goal);
39 goal_.use_start =
false;
40 getInput(
"use_start", use_start);
42 getInput(
"start", goal_.start);
43 goal_.use_start =
true;
46 getInput(
"start_id", goal_.start_id);
47 getInput(
"goal_id", goal_.goal_id);
48 goal_.use_start =
false;
49 goal_.use_poses =
false;
55 setOutput(
"path", result_.result->path);
56 setOutput(
"route", result_.result->route);
57 setOutput(
"planning_time", result_.result->planning_time);
59 setOutput(
"error_code_id", ActionResult::NONE);
60 setOutput(
"error_msg",
"");
61 return BT::NodeStatus::SUCCESS;
66 nav_msgs::msg::Path empty_path;
67 setOutput(
"path", empty_path);
68 nav2_msgs::msg::Route empty_route;
69 setOutput(
"route", empty_route);
70 setOutput(
"planning_time", builtin_interfaces::msg::Duration());
76 setOutput(
"error_code_id", result_.result->error_code);
77 setOutput(
"error_msg", result_.result->error_msg);
78 return BT::NodeStatus::FAILURE;
85 setOutput(
"error_code_id", ActionResult::NONE);
86 setOutput(
"error_msg",
"");
87 return BT::NodeStatus::SUCCESS;
92 setOutput(
"error_code_id", ActionResult::TIMEOUT);
93 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
106 #include "behaviortree_cpp/bt_factory.h"
107 BT_REGISTER_NODES(factory)
109 BT::NodeBuilder builder =
110 [](
const std::string & name,
const BT::NodeConfiguration & config)
112 return std::make_unique<nav2_behavior_tree::ComputeRouteAction>(
113 name,
"compute_route", config);
117 "ComputeRoute", 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::ComputeRoute.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
ComputeRouteAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputeRoute.
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
void on_tick() override
Function to perform some user-defined operation on tick.
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 resetPorts()
Reset output port values on failure.
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.