15 #ifndef NAV2_UTIL__SERVICE_SERVER_HPP_
16 #define NAV2_UTIL__SERVICE_SERVER_HPP_
20 #include "rclcpp/rclcpp.hpp"
21 #include "rclcpp_lifecycle/lifecycle_node.hpp"
30 template<
class ServiceT,
typename NodeT = rclcpp::Node::SharedPtr>
34 using RequestType =
typename ServiceT::Request;
35 using ResponseType =
typename ServiceT::Response;
36 using CallbackType = std::function<void(
const std::shared_ptr<rmw_request_id_t>,
37 const std::shared_ptr<RequestType>, std::shared_ptr<ResponseType>)>;
38 using SharedPtr = std::shared_ptr<ServiceServer<ServiceT, NodeT>>;
41 const std::string & service_name,
43 CallbackType callback,
44 const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
45 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr)
46 : service_name_(service_name), callback_(callback)
48 server_ = node->template create_service<ServiceT>(
50 [
this](
const std::shared_ptr<rmw_request_id_t> request_header,
51 const std::shared_ptr<RequestType> request, std::shared_ptr<ResponseType> response) {
52 this->callback_(request_header, request, response);
57 rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
58 if(!node->has_parameter(
"service_introspection_mode")) {
59 node->declare_parameter(
"service_introspection_mode",
"disabled");
61 std::string service_introspection_mode =
62 node->get_parameter(
"service_introspection_mode").as_string();
63 if (service_introspection_mode ==
"metadata") {
64 introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
65 }
else if (service_introspection_mode ==
"contents") {
66 introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
69 this->server_->configure_introspection(
70 node->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state);
74 std::string service_name_;
75 CallbackType callback_;
76 typename rclcpp::Service<ServiceT>::SharedPtr server_;
A simple wrapper on ROS2 services server.