Nav2 Navigation Stack - kilted  kilted
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 
24 namespace nav2_behavior_tree
25 {
26 
30 class ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::ComputeAndTrackRoute>
31 {
32  using Action = nav2_msgs::action::ComputeAndTrackRoute;
33  using ActionResult = Action::Result;
34 
35 public:
43  const std::string & xml_tag_name,
44  const std::string & action_name,
45  const BT::NodeConfiguration & conf);
46 
50  void on_tick() override;
51 
55  BT::NodeStatus on_success() override;
56 
60  BT::NodeStatus on_aborted() override;
61 
65  BT::NodeStatus on_cancelled() override;
66 
71  void on_timeout() override;
72 
78  void on_wait_for_result(
79  std::shared_ptr<const Action::Feedback> feedback) override;
80 
85 
90  static BT::PortsList providedPorts()
91  {
92  return providedBasicPorts(
93  {
94  BT::InputPort<unsigned int>("start_id", "ID of the start node"),
95  BT::InputPort<unsigned int>("goal_id", "ID of the goal node"),
96  BT::InputPort<geometry_msgs::msg::PoseStamped>(
97  "start",
98  "Start pose of the path if overriding current robot pose and using poses over IDs"),
99  BT::InputPort<geometry_msgs::msg::PoseStamped>(
100  "goal", "Goal pose of the path if using poses over IDs"),
101  BT::InputPort<bool>(
102  "use_start", false,
103  "Whether to use the start pose or the robot's current pose"),
104  BT::InputPort<bool>(
105  "use_poses", false, "Whether to use poses or IDs for start and goal"),
106  BT::OutputPort<builtin_interfaces::msg::Duration>(
107  "execution_duration",
108  "Time taken to compute and track route"),
109  BT::OutputPort<ActionResult::_error_code_type>(
110  "error_code_id", "The compute route error code"),
111  BT::OutputPort<std::string>(
112  "error_msg", "The compute route error msg"),
113  BT::OutputPort<uint16_t>(
114  "last_node_id",
115  "ID of the previous node"),
116  BT::OutputPort<uint16_t>(
117  "next_node_id",
118  "ID of the next node"),
119  BT::OutputPort<uint16_t>(
120  "current_edge_id",
121  "ID of current edge"),
122  BT::OutputPort<nav2_msgs::msg::Route>(
123  "route",
124  "List of RouteNodes to go from start to end"),
125  BT::OutputPort<nav_msgs::msg::Path>(
126  "path",
127  "Path created by ComputeAndTrackRoute node"),
128  BT::OutputPort<bool>(
129  "rerouted",
130  "Whether the plan has rerouted"),
131  });
132  }
133 
134 protected:
135  Action::Feedback feedback_;
136 };
137 
138 } // namespace nav2_behavior_tree
139 
140 #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 on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
void resetFeedbackAndOutputPorts()
Function to set all feedbacks and output ports to be null values.