18 #include "nav2_behavior_tree/plugins/action/compute_and_track_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(
"execution_duration", result_.result->execution_duration);
56 setOutput(
"error_code_id", ActionResult::NONE);
57 setOutput(
"error_msg",
"");
58 return BT::NodeStatus::SUCCESS;
63 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
64 setOutput(
"error_code_id", result_.result->error_code);
65 setOutput(
"error_msg", result_.result->error_msg);
66 return BT::NodeStatus::FAILURE;
72 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
73 setOutput(
"error_code_id", ActionResult::NONE);
74 setOutput(
"error_msg",
"");
75 return BT::NodeStatus::SUCCESS;
80 setOutput(
"error_code_id", ActionResult::TIMEOUT);
81 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
85 std::shared_ptr<const Action::Feedback>)
88 bool use_poses =
false, use_start =
false;
89 getInput(
"use_start", use_start);
90 getInput(
"use_poses", use_poses);
92 if (goal_.use_poses != use_poses) {
97 geometry_msgs::msg::PoseStamped goal;
98 getInput(
"goal", goal);
99 if (goal_.goal != goal) {
100 goal_updated_ =
true;
103 if (goal_.use_start != use_start) {
104 goal_updated_ =
true;
107 geometry_msgs::msg::PoseStamped start;
108 getInput(
"start", start);
109 if (goal_.start != start) {
110 goal_updated_ =
true;
115 unsigned int start_id = 0;
116 unsigned int goal_id = 0;
117 getInput(
"start_id", start_id);
118 getInput(
"goal_id", goal_id);
119 if (goal_.start_id != start_id) {
120 goal_updated_ =
true;
122 if (goal_.goal_id != goal_id) {
123 goal_updated_ =
true;
136 #include "behaviortree_cpp/bt_factory.h"
137 BT_REGISTER_NODES(factory)
139 BT::NodeBuilder builder =
140 [](
const std::string & name,
const BT::NodeConfiguration & config)
142 return std::make_unique<nav2_behavior_tree::ComputeAndTrackRouteAction>(
143 name,
"compute_and_track_route", config);
147 "ComputeAndTrackRoute", builder);
Abstract class representing an action based BT node.
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::ComputeAndTrackRoute.
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.
ComputeAndTrackRouteAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputeAndTrackRouteAction.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
void on_wait_for_result(std::shared_ptr< const Action::Feedback > feedback) override
Function to perform some user-defined operation after a timeout waiting for a result that hasn't been...
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...