Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
service_server.hpp
1 // Copyright (c) 2025 Maurice Alexander Purnawan
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_UTIL__SERVICE_SERVER_HPP_
16 #define NAV2_UTIL__SERVICE_SERVER_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include "rclcpp/rclcpp.hpp"
21 #include "rclcpp_lifecycle/lifecycle_node.hpp"
22 
23 namespace nav2_util
24 {
25 
30 template<class ServiceT, typename NodeT = rclcpp::Node::SharedPtr>
32 {
33 public:
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>>;
39 
40  explicit ServiceServer(
41  const std::string & service_name,
42  const NodeT & node,
43  CallbackType callback,
44  const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
45  rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
46  : service_name_(service_name), callback_(callback)
47  {
48  server_ = node->template create_service<ServiceT>(
49  service_name,
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);
53  },
54  qos,
55  callback_group);
56 
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");
60  }
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;
67  }
68 
69  this->server_->configure_introspection(
70  node->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state);
71  }
72 
73 protected:
74  std::string service_name_;
75  CallbackType callback_;
76  typename rclcpp::Service<ServiceT>::SharedPtr server_;
77 };
78 
79 } // namespace nav2_util
80 
81 
82 #endif // NAV2_UTIL__SERVICE_SERVER_HPP_
A simple wrapper on ROS2 services server.