15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__PAUSE_RESUME_CONTROLLER_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONTROL__PAUSE_RESUME_CONTROLLER_HPP_
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"
32 #include "std_srvs/srv/trigger.hpp"
35 namespace nav2_behavior_tree
38 using Trigger = std_srvs::srv::Trigger;
40 enum state_t {RESUMED, PAUSED, PAUSE_REQUESTED, ON_PAUSE, RESUME_REQUESTED, ON_RESUME};
41 const std::map<state_t, std::string> state_names = {
44 {PAUSE_REQUESTED,
"PAUSE_REQUESTED"},
45 {ON_PAUSE,
"ON_PAUSE"},
46 {RESUME_REQUESTED,
"RESUME_REQUESTED"},
47 {ON_RESUME,
"ON_RESUME"}
49 const std::map<state_t, uint16_t> child_indices = {
91 const std::string & xml_tag_name,
92 const BT::NodeConfiguration & conf);
98 BT::NodeStatus
tick()
override;
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"),
113 [[nodiscard]]
inline state_t getState()
const
120 void pauseServiceCallback(
121 const std::shared_ptr<rmw_request_id_t>,
122 const std::shared_ptr<Trigger::Request> request,
123 std::shared_ptr<Trigger::Response> response);
126 void resumeServiceCallback(
127 const std::shared_ptr<rmw_request_id_t>,
128 const std::shared_ptr<Trigger::Request> request,
129 std::shared_ptr<Trigger::Response> response);
141 void switchToNextState();
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_;
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.