Nav2 Navigation Stack - humble  humble
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  return BT::NodeStatus::SUCCESS;
66 }
67 
69 {
71  setOutput("execution_duration", builtin_interfaces::msg::Duration());
72  return BT::NodeStatus::FAILURE;
73 }
74 
76 {
78  // Set empty error code, action was cancelled
79  setOutput("execution_duration", builtin_interfaces::msg::Duration());
80  return BT::NodeStatus::SUCCESS;
81 }
82 
84  std::shared_ptr<const Action::Feedback> feedback)
85 {
86  // Check for request updates to the goal
87  bool use_poses = false, use_start = false;
88  getInput("use_start", use_start);
89  getInput("use_poses", use_poses);
90 
91  if (goal_.use_poses != use_poses) {
92  goal_updated_ = true;
93  }
94 
95  if (use_poses) {
96  geometry_msgs::msg::PoseStamped goal;
97  getInput("goal", goal);
98  if (goal_.goal != goal) {
99  goal_updated_ = true;
100  }
101 
102  if (goal_.use_start != use_start) {
103  goal_updated_ = true;
104  }
105  if (use_start) {
106  geometry_msgs::msg::PoseStamped start;
107  getInput("start", start);
108  if (goal_.start != start) {
109  goal_updated_ = true;
110  }
111  }
112  } else {
113  // Check if the start and goal IDs have changed
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;
120  }
121  if (goal_.goal_id != goal_id) {
122  goal_updated_ = true;
123  }
124  }
125 
126  // If we're updating the request, we need to fully update the goal
127  // Easier to call on_tick() again than to duplicate the code
128  if (goal_updated_) {
129  on_tick();
130  }
131 
132  if (feedback) {
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);
140  }
141 }
142 
144 {
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);
159 }
160 
161 } // namespace nav2_behavior_tree
162 
163 #include "behaviortree_cpp_v3/bt_factory.h"
164 BT_REGISTER_NODES(factory)
165 {
166  BT::NodeBuilder builder =
167  [](const std::string & name, const BT::NodeConfiguration & config)
168  {
169  return std::make_unique<nav2_behavior_tree::ComputeAndTrackRouteAction>(
170  name, "compute_and_track_route", config);
171  };
172 
173  factory.registerBuilder<nav2_behavior_tree::ComputeAndTrackRouteAction>(
174  "ComputeAndTrackRoute", builder);
175 }
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.