22 using callback_t =
typename rclcpp::Service<ServiceType>::CallbackType;
35 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
const rclcpp::QoS& qos = rclcpp::ServicesQoS());
55 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
const rclcpp::QoS& qos,
56 const rclcpp::CallbackGroup::SharedPtr& callback_group);
67 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
68 const rclcpp::CallbackGroup::SharedPtr& callback_group);
71 rclcpp::CallbackGroup::SharedPtr callback_group_;
72 typename rclcpp::Service<ServiceType>::SharedPtr service_server_;
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24