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)
29 nav_msgs::msg::Path empty_path;
30 nav2_msgs::msg::Route empty_route;
31 feedback_.last_node_id = 0;
32 feedback_.next_node_id = 0;
33 feedback_.current_edge_id = 0;
34 feedback_.route = empty_route;
35 feedback_.path = empty_path;
36 feedback_.rerouted =
false;
41 bool use_poses =
false, use_start =
false;
42 getInput(
"use_poses", use_poses);
44 goal_.use_poses =
true;
45 getInput(
"goal", goal_.goal);
47 goal_.use_start =
false;
48 getInput(
"use_start", use_start);
50 getInput(
"start", goal_.start);
51 goal_.use_start =
true;
54 getInput(
"start_id", goal_.start_id);
55 getInput(
"goal_id", goal_.goal_id);
56 goal_.use_start =
false;
57 goal_.use_poses =
false;
64 setOutput(
"execution_duration", result_.result->execution_duration);
65 setOutput(
"error_code_id", ActionResult::NONE);
66 setOutput(
"error_msg",
"");
67 return BT::NodeStatus::SUCCESS;
73 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
74 setOutput(
"error_code_id", result_.result->error_code);
75 setOutput(
"error_msg", result_.result->error_msg);
76 return BT::NodeStatus::FAILURE;
83 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
84 setOutput(
"error_code_id", ActionResult::NONE);
85 setOutput(
"error_msg",
"");
86 return BT::NodeStatus::SUCCESS;
91 setOutput(
"error_code_id", ActionResult::TIMEOUT);
92 setOutput(
"error_msg",
"Behavior Tree action client timed out waiting.");
96 std::shared_ptr<const Action::Feedback> feedback)
99 bool use_poses =
false, use_start =
false;
100 getInput(
"use_start", use_start);
101 getInput(
"use_poses", use_poses);
103 if (goal_.use_poses != use_poses) {
104 goal_updated_ =
true;
108 geometry_msgs::msg::PoseStamped goal;
109 getInput(
"goal", goal);
110 if (goal_.goal != goal) {
111 goal_updated_ =
true;
114 if (goal_.use_start != use_start) {
115 goal_updated_ =
true;
118 geometry_msgs::msg::PoseStamped start;
119 getInput(
"start", start);
120 if (goal_.start != start) {
121 goal_updated_ =
true;
126 unsigned int start_id = 0;
127 unsigned int goal_id = 0;
128 getInput(
"start_id", start_id);
129 getInput(
"goal_id", goal_id);
130 if (goal_.start_id != start_id) {
131 goal_updated_ =
true;
133 if (goal_.goal_id != goal_id) {
134 goal_updated_ =
true;
145 feedback_ = *feedback;
146 setOutput(
"last_node_id", feedback_.last_node_id);
147 setOutput(
"next_node_id", feedback_.next_node_id);
148 setOutput(
"current_edge_id", feedback_.current_edge_id);
149 setOutput(
"route", feedback_.route);
150 setOutput(
"path", feedback_.path);
151 setOutput(
"rerouted", feedback_.rerouted);
157 nav_msgs::msg::Path empty_path;
158 nav2_msgs::msg::Route empty_route;
159 feedback_.last_node_id = 0;
160 feedback_.next_node_id = 0;
161 feedback_.current_edge_id = 0;
162 feedback_.route = empty_route;
163 feedback_.path = empty_path;
164 feedback_.rerouted =
false;
165 setOutput(
"last_node_id", feedback_.last_node_id);
166 setOutput(
"next_node_id", feedback_.next_node_id);
167 setOutput(
"current_edge_id", feedback_.current_edge_id);
168 setOutput(
"route", feedback_.route);
169 setOutput(
"path", feedback_.path);
170 setOutput(
"rerouted", feedback_.rerouted);
175 #include "behaviortree_cpp/bt_factory.h"
176 BT_REGISTER_NODES(factory)
178 BT::NodeBuilder builder =
179 [](
const std::string & name,
const BT::NodeConfiguration & config)
181 return std::make_unique<nav2_behavior_tree::ComputeAndTrackRouteAction>(
182 name,
"compute_and_track_route", config);
186 "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...
void resetFeedbackAndOutputPorts()
Function to set all feedbacks and output ports to be null values.