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_util/service_client.hpp"
31 namespace nav2_lifecycle_manager
37 enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
52 const std::string & name,
53 std::shared_ptr<rclcpp::Node> parent_node);
60 bool startup(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
65 bool shutdown(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
70 bool pause(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
75 bool resume(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
80 bool reset(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
85 bool configure(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
90 bool cleanup(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
95 SystemStatus
is_active(
const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
98 using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
106 const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
109 rclcpp::Node::SharedPtr node_;
111 nav2_util::ServiceClient<ManageLifecycleNodes>::SharedPtr manager_client_;
112 nav2_util::ServiceClient<std_srvs::srv::Trigger>::SharedPtr is_active_client_;
113 std::string manage_service_name_;
114 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, std::shared_ptr< rclcpp::Node > 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.