Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
compute_and_track_route_action.cpp
1 // Copyright (c) 2025 Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <memory>
16 #include <string>
17 
18 #include "nav2_behavior_tree/plugins/action/compute_and_track_route_action.hpp"
19 
20 namespace nav2_behavior_tree
21 {
22 
24  const std::string & xml_tag_name,
25  const std::string & action_name,
26  const BT::NodeConfiguration & conf)
27 : BtActionNode<Action>(xml_tag_name, action_name, conf)
28 {
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;
37 }
38 
40 {
41  bool use_poses = false, use_start = false;
42  getInput("use_poses", use_poses);
43  if (use_poses) {
44  goal_.use_poses = true;
45  getInput("goal", goal_.goal);
46 
47  goal_.use_start = false;
48  getInput("use_start", use_start);
49  if (use_start) {
50  getInput("start", goal_.start);
51  goal_.use_start = true;
52  }
53  } else {
54  getInput("start_id", goal_.start_id);
55  getInput("goal_id", goal_.goal_id);
56  goal_.use_start = false;
57  goal_.use_poses = false;
58  }
59 }
60 
62 {
64  setOutput("execution_duration", result_.result->execution_duration);
65  setOutput("error_code_id", ActionResult::NONE);
66  return BT::NodeStatus::SUCCESS;
67 }
68 
70 {
72  setOutput("execution_duration", builtin_interfaces::msg::Duration());
73  setOutput("error_code_id", result_.result->error_code);
74  return BT::NodeStatus::FAILURE;
75 }
76 
78 {
80  // Set empty error code, action was cancelled
81  setOutput("execution_duration", builtin_interfaces::msg::Duration());
82  setOutput("error_code_id", ActionResult::NONE);
83  return BT::NodeStatus::SUCCESS;
84 }
85 
87  std::shared_ptr<const Action::Feedback> feedback)
88 {
89  // Check for request updates to the goal
90  bool use_poses = false, use_start = false;
91  getInput("use_start", use_start);
92  getInput("use_poses", use_poses);
93 
94  if (goal_.use_poses != use_poses) {
95  goal_updated_ = true;
96  }
97 
98  if (use_poses) {
99  geometry_msgs::msg::PoseStamped goal;
100  getInput("goal", goal);
101  if (goal_.goal != goal) {
102  goal_updated_ = true;
103  }
104 
105  if (goal_.use_start != use_start) {
106  goal_updated_ = true;
107  }
108  if (use_start) {
109  geometry_msgs::msg::PoseStamped start;
110  getInput("start", start);
111  if (goal_.start != start) {
112  goal_updated_ = true;
113  }
114  }
115  } else {
116  // Check if the start and goal IDs have changed
117  unsigned int start_id = 0;
118  unsigned int goal_id = 0;
119  getInput("start_id", start_id);
120  getInput("goal_id", goal_id);
121  if (goal_.start_id != start_id) {
122  goal_updated_ = true;
123  }
124  if (goal_.goal_id != goal_id) {
125  goal_updated_ = true;
126  }
127  }
128 
129  // If we're updating the request, we need to fully update the goal
130  // Easier to call on_tick() again than to duplicate the code
131  if (goal_updated_) {
132  on_tick();
133  }
134 
135  if (feedback) {
136  feedback_ = *feedback;
137  setOutput("last_node_id", feedback_.last_node_id);
138  setOutput("next_node_id", feedback_.next_node_id);
139  setOutput("current_edge_id", feedback_.current_edge_id);
140  setOutput("route", feedback_.route);
141  setOutput("path", feedback_.path);
142  setOutput("rerouted", feedback_.rerouted);
143  }
144 }
145 
147 {
148  nav_msgs::msg::Path empty_path;
149  nav2_msgs::msg::Route empty_route;
150  feedback_.last_node_id = 0;
151  feedback_.next_node_id = 0;
152  feedback_.current_edge_id = 0;
153  feedback_.route = empty_route;
154  feedback_.path = empty_path;
155  feedback_.rerouted = false;
156  setOutput("last_node_id", feedback_.last_node_id);
157  setOutput("next_node_id", feedback_.next_node_id);
158  setOutput("current_edge_id", feedback_.current_edge_id);
159  setOutput("route", feedback_.route);
160  setOutput("path", feedback_.path);
161  setOutput("rerouted", feedback_.rerouted);
162 }
163 
164 } // namespace nav2_behavior_tree
165 
166 #include "behaviortree_cpp/bt_factory.h"
167 BT_REGISTER_NODES(factory)
168 {
169  BT::NodeBuilder builder =
170  [](const std::string & name, const BT::NodeConfiguration & config)
171  {
172  return std::make_unique<nav2_behavior_tree::ComputeAndTrackRouteAction>(
173  name, "compute_and_track_route", config);
174  };
175 
176  factory.registerBuilder<nav2_behavior_tree::ComputeAndTrackRouteAction>(
177  "ComputeAndTrackRoute", builder);
178 }
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.