Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
compute_route_action.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_ROUTE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_ROUTE_ACTION_HPP_
17 
18 #include <string>
19 
20 #include "nav2_msgs/action/compute_route.hpp"
21 #include "nav_msgs/msg/path.h"
22 #include "nav2_behavior_tree/bt_action_node.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 
25 namespace nav2_behavior_tree
26 {
27 
31 class ComputeRouteAction : public BtActionNode<nav2_msgs::action::ComputeRoute>
32 {
33  using Action = nav2_msgs::action::ComputeRoute;
34  using ActionResult = Action::Result;
35 
36 public:
44  const std::string & xml_tag_name,
45  const std::string & action_name,
46  const BT::NodeConfiguration & conf);
47 
51  void on_tick() override;
52 
56  BT::NodeStatus on_success() override;
57 
61  BT::NodeStatus on_aborted() override;
62 
66  BT::NodeStatus on_cancelled() override;
67 
71  void halt() override;
72 
76  void resetPorts();
77 
82  static BT::PortsList providedPorts()
83  {
84  return providedBasicPorts(
85  {
86  BT::InputPort<unsigned int>("start_id", "ID of the start node"),
87  BT::InputPort<unsigned int>("goal_id", "ID of the goal node"),
88  BT::InputPort<geometry_msgs::msg::PoseStamped>(
89  "start",
90  "Start pose of the path if overriding current robot pose and using poses over IDs"),
91  BT::InputPort<geometry_msgs::msg::PoseStamped>(
92  "goal", "Goal pose of the path if using poses over IDs"),
93  BT::InputPort<bool>(
94  "use_start", false,
95  "Whether to use the start pose or the robot's current pose"),
96  BT::InputPort<bool>(
97  "use_poses", false, "Whether to use poses or IDs for start and goal"),
98  BT::OutputPort<ActionResult::_route_type>(
99  "route", "The route computed by ComputeRoute node"),
100  BT::OutputPort<builtin_interfaces::msg::Duration>(
101  "planning_time",
102  "Time taken to compute route"),
103  BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputeRoute node"),
104  });
105  }
106 };
107 
108 } // namespace nav2_behavior_tree
109 
110 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_ROUTE_ACTION_HPP_
Abstract class representing an action based BT node.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call pro...
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.
static BT::PortsList providedPorts()
Creates list of BT ports.
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.