ROS2ServiceBase.h 3.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091
  1. /*
  2. * Copyright (c) Contributors to the Open 3D Engine Project.
  3. * For complete copyright and license terms please see the LICENSE at the root of this distribution.
  4. *
  5. * SPDX-License-Identifier: Apache-2.0 OR MIT
  6. *
  7. */
  8. #pragma once
  9. #include <AzCore/std/containers/unordered_set.h>
  10. #include <AzCore/std/optional.h>
  11. #include <Interfaces/IROS2HandlerBase.h>
  12. #include <Utils/RegistryUtils.h>
  13. #include <rclcpp/service.hpp>
  14. #include <simulation_interfaces/msg/simulator_features.hpp>
  15. namespace ROS2SimulationInterfaces
  16. {
  17. //! Base for each ROS 2 service handler, forces declaration of features provided by the handler
  18. //! combined information along all ROS 2 handlers gives information about simulation features
  19. //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
  20. using SimulationFeatures = simulation_interfaces::msg::SimulatorFeatures;
  21. template<typename RosServiceType>
  22. class ROS2ServiceBase : public virtual IROS2HandlerBase
  23. {
  24. public:
  25. using Request = typename RosServiceType::Request;
  26. using Response = typename RosServiceType::Response;
  27. using ServiceHandle = std::shared_ptr<rclcpp::Service<RosServiceType>>;
  28. virtual ~ROS2ServiceBase() = default;
  29. void Initialize(rclcpp::Node::SharedPtr& node) override
  30. {
  31. CreateService(node);
  32. }
  33. void SendResponse(Response response)
  34. {
  35. AZ_Assert(m_serviceHandle, "Failed to get m_serviceHandle");
  36. AZ_Assert(m_lastRequestHeader, "Failed to get last request header ptr");
  37. m_serviceHandle->send_response(*m_lastRequestHeader, response);
  38. }
  39. protected:
  40. //! This function is called when a service request is received.
  41. virtual AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) = 0;
  42. //! return features id defined by the handler, ids must follow the definition inside standard:
  43. //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
  44. AZStd::unordered_set<SimulationFeatureType> GetProvidedFeatures() override
  45. {
  46. return {};
  47. };
  48. private:
  49. void CreateService(rclcpp::Node::SharedPtr& node)
  50. {
  51. // get the service name from the type name
  52. AZStd::string serviceName = RegistryUtilities::GetName(GetTypeName());
  53. if (serviceName.empty())
  54. {
  55. // if the service name is empty, use the default name
  56. serviceName = GetDefaultName();
  57. }
  58. const std::string serviceNameStr{ serviceName.c_str(), serviceName.size() };
  59. m_serviceHandle = node->create_service<RosServiceType>(
  60. serviceNameStr,
  61. [this](
  62. const ServiceHandle service_handle,
  63. const std::shared_ptr<rmw_request_id_t> header,
  64. const std::shared_ptr<Request> request)
  65. {
  66. m_lastRequestHeader = header;
  67. auto response = HandleServiceRequest(header, *request);
  68. // if no response passed it means, that handleServiceRequest will send response in defined callback after time consuming
  69. // task, header needs to be cached
  70. if (response.has_value())
  71. {
  72. service_handle->send_response(*header, response.value());
  73. }
  74. });
  75. }
  76. std::shared_ptr<rmw_request_id_t> m_lastRequestHeader = nullptr;
  77. ServiceHandle m_serviceHandle;
  78. };
  79. } // namespace ROS2SimulationInterfaces