25 using callback_t =
typename rclcpp::Service<ServiceType>::CallbackType;
38 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
const rclcpp::QoS& qos = rclcpp::ServicesQoS());
58 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
const rclcpp::QoS& qos,
59 const rclcpp::CallbackGroup::SharedPtr& callback_group);
71 template <
typename ClassType>
73 mrs_lib::Task<bool> (ClassType::*method)(
const std::shared_ptr<typename ServiceType::Request> request,
74 const std::shared_ptr<typename ServiceType::Response> response),
75 ClassType* instance,
const rclcpp::QoS& qos,
const rclcpp::CallbackGroup::SharedPtr& callback_group);
86 ServiceServerHandler(rclcpp::Node::SharedPtr& node,
const std::string& address,
const callback_t& cbk,
87 const rclcpp::CallbackGroup::SharedPtr& callback_group);
90 rclcpp::CallbackGroup::SharedPtr callback_group_;
91 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