15 #include "nav2_util/lifecycle_service_client.hpp"
21 #include "lifecycle_msgs/srv/change_state.hpp"
22 #include "lifecycle_msgs/srv/get_state.hpp"
24 using nav2_util::generate_internal_node;
25 using std::chrono::seconds;
26 using std::make_shared;
28 using namespace std::chrono_literals;
33 LifecycleServiceClient::LifecycleServiceClient(
const string & lifecycle_node_name)
34 : node_(generate_internal_node(lifecycle_node_name +
"_lifecycle_client")),
35 change_state_(lifecycle_node_name +
"/change_state", node_),
36 get_state_(lifecycle_node_name +
"/get_state", node_)
40 while (!get_state_.wait_for_service(2s)) {
42 node_->get_logger(),
"Waiting for service %s...", get_state_.getServiceName().c_str());
47 LifecycleServiceClient::LifecycleServiceClient(
48 const string & lifecycle_node_name,
49 rclcpp::Node::SharedPtr parent_node)
51 change_state_(lifecycle_node_name +
"/change_state", node_),
52 get_state_(lifecycle_node_name +
"/get_state", node_)
56 while (!get_state_.wait_for_service(2s)) {
58 node_->get_logger(),
"Waiting for service %s...", get_state_.getServiceName().c_str());
63 bool LifecycleServiceClient::change_state(
64 const uint8_t transition,
65 const seconds timeout)
67 if (!change_state_.wait_for_service(timeout)) {
68 throw std::runtime_error(
"change_state service is not available!");
71 auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
72 request->transition.id = transition;
73 auto response = change_state_.invoke(request, timeout);
74 return response.get();
77 bool LifecycleServiceClient::change_state(
78 std::uint8_t transition)
80 if (!change_state_.wait_for_service(5s)) {
81 throw std::runtime_error(
"change_state service is not available!");
84 auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
85 auto response = std::make_shared<lifecycle_msgs::srv::ChangeState::Response>();
86 request->transition.id = transition;
87 return change_state_.invoke(request, response);
90 uint8_t LifecycleServiceClient::get_state(
91 const seconds timeout)
93 if (!get_state_.wait_for_service(timeout)) {
94 throw std::runtime_error(
"get_state service is not available!");
97 auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();
98 auto result = get_state_.invoke(request, timeout);
99 return result->current_state.id;