15 #ifndef NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
16 #define NAV2_LIFECYCLE_MANAGER__LIFECYCLE_MANAGER_CLIENT_HPP_
21 #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
22 #include "geometry_msgs/msg/quaternion.hpp"
23 #include "nav2_msgs/action/navigate_to_pose.hpp"
24 #include "rclcpp/rclcpp.hpp"
25 #include "rclcpp_action/rclcpp_action.hpp"
26 #include "std_srvs/srv/empty.hpp"
27 #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
28 #include "std_srvs/srv/trigger.hpp"
29 #include "nav2_ros_common/lifecycle_node.hpp"
30 #include "nav2_ros_common/service_client.hpp"
32 namespace nav2_lifecycle_manager
38 enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
52 template<
typename NodeT>
54 const std::string & name,
57 manage_service_name_ = name + std::string(
"/manage_nodes");
58 active_service_name_ = name + std::string(
"/is_active");
61 logger_ = parent_node->get_logger();
66 manager_client_ = nav2::interfaces::create_client<ManageLifecycleNodes>(
67 parent_node, manage_service_name_,
true );
68 is_active_client_ = nav2::interfaces::create_client<std_srvs::srv::Trigger>(
69 parent_node, active_service_name_,
true );
77 bool startup(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
82 bool shutdown(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
87 bool pause(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
92 bool resume(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
97 bool reset(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
102 bool configure(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
107 bool cleanup(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
112 SystemStatus
is_active(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
115 using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
123 const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
126 rclcpp::Node::SharedPtr node_;
127 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_lifecycle_manager_client")};
129 nav2::ServiceClient<ManageLifecycleNodes>::SharedPtr manager_client_;
130 nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr is_active_client_;
131 std::string manage_service_name_;
132 std::string active_service_name_;
bool cleanup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make cleanup service call.
LifecycleManagerClient(const std::string &name, NodeT parent_node)
A constructor for LifeCycleMangerClient.
bool pause(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make pause service call.
SystemStatus is_active(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Check if lifecycle node manager server is active.
bool shutdown(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make shutdown service call.
bool reset(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make reset service call.
bool startup(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make start up service call.
bool configure(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make configure service call.
bool callService(uint8_t command, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
A generic method used to call startup, shutdown, etc.
bool resume(const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
Make resume service call.