19 #include "nav2_behavior_tree/plugins/control/pause_resume_controller.hpp"
22 #include "behaviortree_cpp/bt_factory.h"
24 namespace nav2_behavior_tree
27 using namespace std::placeholders;
30 const std::string & xml_tag_name,
31 const BT::NodeConfiguration & conf)
32 : BT::ControlNode(xml_tag_name, conf)
34 auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
38 cb_group_ = node->create_callback_group(
39 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
42 std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
44 executor_->add_callback_group(cb_group_, node->get_node_base_interface());
46 std::string pause_service_name;
47 getInput(
"pause_service_name", pause_service_name);
48 pause_srv_ = node->create_service<Trigger>(
50 std::bind(&PauseResumeController::pauseServiceCallback,
this, _1, _2, _3),
53 std::string resume_service_name;
54 getInput(
"resume_service_name", resume_service_name);
55 resume_srv_ = node->create_service<Trigger>(
57 std::bind(&PauseResumeController::resumeServiceCallback,
this, _1, _2, _3),
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) +
")");
70 if (status() == BT::NodeStatus::IDLE) {
73 setStatus(BT::NodeStatus::RUNNING);
75 executor_->spin_some();
78 if (state_ == PAUSE_REQUESTED || state_ == RESUME_REQUESTED) {
84 const uint16_t child_idx = child_indices.at(state_);
85 if (children_nodes_.size() <= child_idx) {
87 return BT::NodeStatus::RUNNING;
91 const BT::NodeStatus child_status =
92 children_nodes_[child_indices.at(state_)]->executeTick();
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) {
101 return BT::NodeStatus::SUCCESS;
105 return BT::NodeStatus::RUNNING;
106 case BT::NodeStatus::FAILURE:
108 logger_,
"%s child returned FAILURE", state_names.at(state_).c_str());
109 return BT::NodeStatus::FAILURE;
111 throw std::runtime_error(
"A child node must never return IDLE");
115 void PauseResumeController::switchToNextState()
117 static const std::map<state_t, state_t> next_states = {
118 {PAUSE_REQUESTED, ON_PAUSE},
120 {RESUME_REQUESTED, ON_RESUME},
124 if (state_ == PAUSED || state_ == RESUMED) {
129 state_ = next_states.at(state_);
130 RCLCPP_INFO(logger_,
"Switched to state: %s", state_names.at(state_).c_str());
133 void PauseResumeController::pauseServiceCallback(
134 const std::shared_ptr<rmw_request_id_t>,
135 const std::shared_ptr<Trigger::Request>,
136 std::shared_ptr<Trigger::Response> response)
138 if (state_ != PAUSED) {
139 RCLCPP_INFO(logger_,
"Received pause request");
140 response->success =
true;
141 state_ = PAUSE_REQUESTED;
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;
151 void PauseResumeController::resumeServiceCallback(
152 const std::shared_ptr<rmw_request_id_t>,
153 const std::shared_ptr<Trigger::Request>,
154 std::shared_ptr<Trigger::Response> response)
156 if (state_ == PAUSED) {
157 RCLCPP_INFO(logger_,
"Received resume request");
158 response->success =
true;
159 state_ = RESUME_REQUESTED;
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;
177 BT_REGISTER_NODES(factory)
179 BT::NodeBuilder builder =
180 [](
const std::string & name,
const BT::NodeConfiguration & config)
182 return std::make_unique<nav2_behavior_tree::PauseResumeController>(
187 "PauseResumeController", builder);
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.