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 return BT::NodeStatus::SUCCESS;
71 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
72 return BT::NodeStatus::FAILURE;
79 setOutput(
"execution_duration", builtin_interfaces::msg::Duration());
80 return BT::NodeStatus::SUCCESS;
84 std::shared_ptr<const Action::Feedback> feedback)
87 bool use_poses =
false, use_start =
false;
88 getInput(
"use_start", use_start);
89 getInput(
"use_poses", use_poses);
91 if (goal_.use_poses != use_poses) {
96 geometry_msgs::msg::PoseStamped goal;
97 getInput(
"goal", goal);
98 if (goal_.goal != goal) {
102 if (goal_.use_start != use_start) {
103 goal_updated_ =
true;
106 geometry_msgs::msg::PoseStamped start;
107 getInput(
"start", start);
108 if (goal_.start != start) {
109 goal_updated_ =
true;
114 unsigned int start_id = 0;
115 unsigned int goal_id = 0;
116 getInput(
"start_id", start_id);
117 getInput(
"goal_id", goal_id);
118 if (goal_.start_id != start_id) {
119 goal_updated_ =
true;
121 if (goal_.goal_id != goal_id) {
122 goal_updated_ =
true;
133 feedback_ = *feedback;
134 setOutput(
"last_node_id", feedback_.last_node_id);
135 setOutput(
"next_node_id", feedback_.next_node_id);
136 setOutput(
"current_edge_id", feedback_.current_edge_id);
137 setOutput(
"route", feedback_.route);
138 setOutput(
"path", feedback_.path);
139 setOutput(
"rerouted", feedback_.rerouted);
145 nav_msgs::msg::Path empty_path;
146 nav2_msgs::msg::Route empty_route;
147 feedback_.last_node_id = 0;
148 feedback_.next_node_id = 0;
149 feedback_.current_edge_id = 0;
150 feedback_.route = empty_route;
151 feedback_.path = empty_path;
152 feedback_.rerouted =
false;
153 setOutput(
"last_node_id", feedback_.last_node_id);
154 setOutput(
"next_node_id", feedback_.next_node_id);
155 setOutput(
"current_edge_id", feedback_.current_edge_id);
156 setOutput(
"route", feedback_.route);
157 setOutput(
"path", feedback_.path);
158 setOutput(
"rerouted", feedback_.rerouted);
163 #include "behaviortree_cpp_v3/bt_factory.h"
164 BT_REGISTER_NODES(factory)
166 BT::NodeBuilder builder =
167 [](
const std::string & name,
const BT::NodeConfiguration & config)
169 return std::make_unique<nav2_behavior_tree::ComputeAndTrackRouteAction>(
170 name,
"compute_and_track_route", config);
174 "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 resetFeedbackAndOutputPorts()
Function to set all feedbacks and output ports to be null values.