Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
compute_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_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 }
30 
32 {
33  bool use_poses = false, use_start = false;
34  getInput("use_poses", use_poses);
35  if (use_poses) {
36  goal_.use_poses = true;
37  getInput("goal", goal_.goal);
38 
39  goal_.use_start = false;
40  getInput("use_start", use_start);
41  if (use_start) {
42  getInput("start", goal_.start);
43  goal_.use_start = true;
44  }
45  } else {
46  getInput("start_id", goal_.start_id);
47  getInput("goal_id", goal_.goal_id);
48  goal_.use_start = false;
49  goal_.use_poses = false;
50  }
51 }
52 
54 {
55  setOutput("path", result_.result->path);
56  setOutput("route", result_.result->route);
57  setOutput("planning_time", result_.result->planning_time);
58  return BT::NodeStatus::SUCCESS;
59 }
60 
62 {
63  nav_msgs::msg::Path empty_path;
64  setOutput("path", empty_path);
65  nav2_msgs::msg::Route empty_route;
66  setOutput("route", empty_route);
67  setOutput("planning_time", builtin_interfaces::msg::Duration());
68 }
69 
71 {
72  resetPorts();
73  return BT::NodeStatus::FAILURE;
74 }
75 
77 {
78  resetPorts();
79  return BT::NodeStatus::SUCCESS;
80 }
81 
83 {
84  resetPorts();
86 }
87 
88 } // namespace nav2_behavior_tree
89 
90 #include "behaviortree_cpp_v3/bt_factory.h"
91 BT_REGISTER_NODES(factory)
92 {
93  BT::NodeBuilder builder =
94  [](const std::string & name, const BT::NodeConfiguration & config)
95  {
96  return std::make_unique<nav2_behavior_tree::ComputeRouteAction>(
97  name, "compute_route", config);
98  };
99 
100  factory.registerBuilder<nav2_behavior_tree::ComputeRouteAction>(
101  "ComputeRoute", builder);
102 }
Abstract class representing an action based BT node.
void halt() override
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 ...
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::ComputeRoute.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
ComputeRouteAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputeRoute.
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
void on_tick() override
Function to perform some user-defined operation on tick.
void resetPorts()
Reset output port values on failure.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.