Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
pause_resume_controller.hpp
1 // Copyright (c) 2025 Enjoy Robotics
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__CONTROL__PAUSE_RESUME_CONTROLLER_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__PAUSE_RESUME_CONTROLLER_HPP_
17 
18 // Other includes
19 #include <string>
20 #include <memory>
21 #include <map>
22 
23 // ROS includes
24 #include "rclcpp/rclcpp.hpp"
25 #include "rclcpp/callback_group.hpp"
26 #include "rclcpp/executors/single_threaded_executor.hpp"
27 #include "behaviortree_cpp/control_node.h"
28 #include "nav2_ros_common/service_server.hpp"
29 #include "nav2_ros_common/lifecycle_node.hpp"
30 
31 // Interface definitions
32 #include "std_srvs/srv/trigger.hpp"
33 
34 
35 namespace nav2_behavior_tree
36 {
37 
38 using Trigger = std_srvs::srv::Trigger;
39 
40 enum state_t {RESUMED, PAUSED, PAUSE_REQUESTED, ON_PAUSE, RESUME_REQUESTED, ON_RESUME};
41 const std::map<state_t, std::string> state_names = {
42  {RESUMED, "RESUMED"},
43  {PAUSED, "PAUSED"},
44  {PAUSE_REQUESTED, "PAUSE_REQUESTED"},
45  {ON_PAUSE, "ON_PAUSE"},
46  {RESUME_REQUESTED, "RESUME_REQUESTED"},
47  {ON_RESUME, "ON_RESUME"}
48 };
49 const std::map<state_t, uint16_t> child_indices = {
50  {RESUMED, 0},
51  {PAUSED, 1},
52  {ON_PAUSE, 2},
53  {ON_RESUME, 3}
54 };
55 
56 /* @brief Controlled through service calls to pause and resume the execution of the tree
57  * It has one mandatory child for the RESUMED, and three optional for the PAUSED state,
58  * the ON_PAUSE event and the ON_RESUME event.
59  * It has two input ports:
60  * - pause_service_name: name of the service to pause
61  * - resume_service_name: name of the service to resume
62  *
63  * Usage:
64  * <PauseResumeController pause_service_name="/pause" resume_service_name="/resume">
65  * <!-- RESUMED branch -->
66  *
67  * <!-- PAUSED branch (optional) -->
68  *
69  * <!-- ON_PAUSE branch (optional) -->
70  *
71  * <!-- ON_RESUME branch (optional) -->
72  * </PauseResumeController>
73  *
74  * The controller starts in RESUMED state, and ticks it until it returns success.
75  * When the pause service is called, ON_PAUSE is ticked until completion,
76  * then the controller switches to PAUSED state.
77  * When the resume service is called, ON_RESUME is ticked until completion,
78  * then the controller switches back to RESUMED state.
79  *
80  * The controller only returns success when the RESUMED child returns success.
81  * The controller returns failure if any child returns failure.
82  * In any other case, it returns running.
83  */
84 
85 
86 class PauseResumeController : public BT::ControlNode
87 {
88 public:
91  const std::string & xml_tag_name,
92  const BT::NodeConfiguration & conf);
93 
95  void halt() override;
96 
98  BT::NodeStatus tick() override;
99 
101  static BT::PortsList providedPorts()
102  {
103  return {
104  BT::InputPort<std::string>(
105  "pause_service_name",
106  "Name of the service to pause"),
107  BT::InputPort<std::string>(
108  "resume_service_name",
109  "Name of the service to resume"),
110  };
111  }
112 
113  [[nodiscard]] inline state_t getState() const
114  {
115  return state_;
116  }
117 
118 private:
120  void pauseServiceCallback(
121  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
122  const std::shared_ptr<Trigger::Request> request,
123  std::shared_ptr<Trigger::Response> response);
124 
126  void resumeServiceCallback(
127  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
128  const std::shared_ptr<Trigger::Request> request,
129  std::shared_ptr<Trigger::Response> response);
130 
141  void switchToNextState();
142 
143  rclcpp::Logger logger_{rclcpp::get_logger("PauseResumeController")};
144  rclcpp::CallbackGroup::SharedPtr cb_group_;
145  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
146  nav2::ServiceServer<Trigger>::SharedPtr pause_srv_;
147  nav2::ServiceServer<Trigger>::SharedPtr resume_srv_;
148  state_t state_;
149 };
150 
151 } // namespace nav2_behavior_tree
152 
153 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__PAUSE_RESUME_CONTROLLER_HPP_
PauseResumeController(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
Constructor.
BT::NodeStatus tick() override
Handle transitions if requested and tick child related to the actual state.
static BT::PortsList providedPorts()
Declare ports.
void halt() override
Reset state and go to Idle.