Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
pause_resume_controller.cpp
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 // Other includes
16 #include <functional>
17 
18 // ROS includes
19 #include "nav2_behavior_tree/plugins/control/pause_resume_controller.hpp"
20 
21 // Other includes
22 #include "behaviortree_cpp/bt_factory.h"
23 
24 namespace nav2_behavior_tree
25 {
26 
27 using namespace std::placeholders;
28 
30  const std::string & xml_tag_name,
31  const BT::NodeConfiguration & conf)
32 : BT::ControlNode(xml_tag_name, conf)
33 {
34  auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
35  state_ = RESUMED;
36 
37  // Create a separate cb group with a separate executor to spin
38  cb_group_ = node->create_callback_group(
39  rclcpp::CallbackGroupType::MutuallyExclusive, false);
40 
41  executor_ =
42  std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
43 
44  executor_->add_callback_group(cb_group_, node->get_node_base_interface());
45 
46  std::string pause_service_name;
47  getInput("pause_service_name", pause_service_name);
48  pause_srv_ = node->create_service<Trigger>(
49  pause_service_name,
50  std::bind(&PauseResumeController::pauseServiceCallback, this, _1, _2, _3),
51  cb_group_);
52 
53  std::string resume_service_name;
54  getInput("resume_service_name", resume_service_name);
55  resume_srv_ = node->create_service<Trigger>(
56  resume_service_name,
57  std::bind(&PauseResumeController::resumeServiceCallback, this, _1, _2, _3),
58  cb_group_);
59 }
60 
62 {
63  unsigned int children_count = children_nodes_.size();
64  if (children_count < 1 || children_count > 4) {
65  throw std::runtime_error(
66  "PauseNode must have at least one and at most four children "
67  "(currently has " + std::to_string(children_count) + ")");
68  }
69 
70  if (status() == BT::NodeStatus::IDLE) {
71  state_ = RESUMED;
72  }
73  setStatus(BT::NodeStatus::RUNNING);
74 
75  executor_->spin_some();
76 
77  // If pause / resume requested, reset children and switch to transient child
78  if (state_ == PAUSE_REQUESTED || state_ == RESUME_REQUESTED) {
79  resetChildren();
80  switchToNextState();
81  }
82 
83  // Return RUNNING and do nothing if specific child is not used
84  const uint16_t child_idx = child_indices.at(state_);
85  if (children_nodes_.size() <= child_idx) {
86  switchToNextState();
87  return BT::NodeStatus::RUNNING;
88  }
89 
90  // If child is used, tick it
91  const BT::NodeStatus child_status =
92  children_nodes_[child_indices.at(state_)]->executeTick();
93 
94  switch (child_status) {
95  case BT::NodeStatus::RUNNING:
96  return BT::NodeStatus::RUNNING;
97  case BT::NodeStatus::SUCCESS:
98  case BT::NodeStatus::SKIPPED:
99  if (state_ == RESUMED) {
100  // Resumed child returned SUCCESS, we're done
101  return BT::NodeStatus::SUCCESS;
102  }
103  switchToNextState();
104  // If any branch other than RESUMED returned SUCCESS, keep ticking
105  return BT::NodeStatus::RUNNING;
106  case BT::NodeStatus::FAILURE:
107  RCLCPP_ERROR(
108  logger_, "%s child returned FAILURE", state_names.at(state_).c_str());
109  return BT::NodeStatus::FAILURE;
110  default:
111  throw std::runtime_error("A child node must never return IDLE");
112  }
113 }
114 
115 void PauseResumeController::switchToNextState()
116 {
117  static const std::map<state_t, state_t> next_states = {
118  {PAUSE_REQUESTED, ON_PAUSE},
119  {ON_PAUSE, PAUSED},
120  {RESUME_REQUESTED, ON_RESUME},
121  {ON_RESUME, RESUMED}
122  };
123 
124  if (state_ == PAUSED || state_ == RESUMED) {
125  // No next state, do nothing
126  return;
127  }
128 
129  state_ = next_states.at(state_);
130  RCLCPP_INFO(logger_, "Switched to state: %s", state_names.at(state_).c_str());
131 }
132 
133 void PauseResumeController::pauseServiceCallback(
134  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
135  const std::shared_ptr<Trigger::Request>/*request*/,
136  std::shared_ptr<Trigger::Response> response)
137 {
138  if (state_ != PAUSED) {
139  RCLCPP_INFO(logger_, "Received pause request");
140  response->success = true;
141  state_ = PAUSE_REQUESTED;
142  return;
143  }
144 
145  std::string warn_message = "PauseResumeController BT node already in state PAUSED";
146  RCLCPP_WARN(logger_, "%s", warn_message.c_str());
147  response->success = false;
148  response->message = warn_message;
149 }
150 
151 void PauseResumeController::resumeServiceCallback(
152  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
153  const std::shared_ptr<Trigger::Request>/*request*/,
154  std::shared_ptr<Trigger::Response> response)
155 {
156  if (state_ == PAUSED) {
157  RCLCPP_INFO(logger_, "Received resume request");
158  response->success = true;
159  state_ = RESUME_REQUESTED;
160  return;
161  }
162 
163  std::string warn_message = "PauseResumeController BT node not in state PAUSED";
164  RCLCPP_WARN(logger_, "%s", warn_message.c_str());
165  response->success = false;
166  response->message = warn_message;
167 }
168 
170 {
171  state_ = RESUMED;
172  ControlNode::halt();
173 }
174 
175 } // namespace nav2_behavior_tree
176 
177 BT_REGISTER_NODES(factory)
178 {
179  BT::NodeBuilder builder =
180  [](const std::string & name, const BT::NodeConfiguration & config)
181  {
182  return std::make_unique<nav2_behavior_tree::PauseResumeController>(
183  name, config);
184  };
185 
186  factory.registerBuilder<nav2_behavior_tree::PauseResumeController>(
187  "PauseResumeController", builder);
188 }
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.
void halt() override
Reset state and go to Idle.