Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
compute_and_track_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_AND_TRACK_ROUTE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_ROUTE_ACTION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "nav2_msgs/action/compute_and_track_route.hpp"
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 ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::ComputeAndTrackRoute>
32 {
33  using Action = nav2_msgs::action::ComputeAndTrackRoute;
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 
73  void on_wait_for_result(
74  std::shared_ptr<const Action::Feedback> feedback) override;
75 
80 
85  static BT::PortsList providedPorts()
86  {
87  return providedBasicPorts(
88  {
89  BT::InputPort<unsigned int>("start_id", "ID of the start node"),
90  BT::InputPort<unsigned int>("goal_id", "ID of the goal node"),
91  BT::InputPort<geometry_msgs::msg::PoseStamped>(
92  "start",
93  "Start pose of the path if overriding current robot pose and using poses over IDs"),
94  BT::InputPort<geometry_msgs::msg::PoseStamped>(
95  "goal", "Goal pose of the path if using poses over IDs"),
96  BT::InputPort<bool>(
97  "use_start", false,
98  "Whether to use the start pose or the robot's current pose"),
99  BT::InputPort<bool>(
100  "use_poses", false, "Whether to use poses or IDs for start and goal"),
101  BT::OutputPort<builtin_interfaces::msg::Duration>(
102  "execution_duration",
103  "Time taken to compute and track route"),
104  BT::OutputPort<uint16_t>(
105  "last_node_id",
106  "ID of the previous node"),
107  BT::OutputPort<uint16_t>(
108  "next_node_id",
109  "ID of the next node"),
110  BT::OutputPort<uint16_t>(
111  "current_edge_id",
112  "ID of current edge"),
113  BT::OutputPort<nav2_msgs::msg::Route>(
114  "route",
115  "List of RouteNodes to go from start to end"),
116  BT::OutputPort<nav_msgs::msg::Path>(
117  "path",
118  "Path created by ComputeAndTrackRoute node"),
119  BT::OutputPort<bool>(
120  "rerouted",
121  "Whether the plan has rerouted"),
122  });
123  }
124 
125 protected:
126  Action::Feedback feedback_;
127 };
128 
129 } // namespace nav2_behavior_tree
130 
131 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_AND_TRACK_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::ComputeAndTrackRoute.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
static BT::PortsList providedPorts()
Creates list of BT ports.
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.