mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
mrs_lib::ServiceServerHandler< ServiceType > Class Template Reference

user wrapper of the service client handler implementation More...

#include <service_server_handler.h>

Public Types

using callback_t = typename rclcpp::Service< ServiceType >::CallbackType
 

Public Member Functions

 ServiceServerHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const callback_t &cbk, const rclcpp::QoS &qos=rclcpp::ServicesQoS())
 The main constructor with all the options.
 
 ServiceServerHandler ()
 Default constructor to avoid having to use pointers.
 
 ServiceServerHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const callback_t &cbk, const rclcpp::QoS &qos, const rclcpp::CallbackGroup::SharedPtr &callback_group)
 A convenience constructor.
 
 ServiceServerHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const callback_t &cbk, const rclcpp::CallbackGroup::SharedPtr &callback_group)
 A convenience constructor.
 

Detailed Description

template<class ServiceType>
class mrs_lib::ServiceServerHandler< ServiceType >

user wrapper of the service client handler implementation

Constructor & Destructor Documentation

◆ ServiceServerHandler() [1/4]

template<class ServiceType >
mrs_lib::ServiceServerHandler< ServiceType >::ServiceServerHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const callback_t &  cbk,
const rclcpp::QoS &  qos = rclcpp::ServicesQoS() 
)

The main constructor with all the options.

This variant initializes a new MutuallyExclusive callback group for the service client, which is the intended default behavior to avoid deadlocks when using the callSync() method. For a more detailed explanation of the parameters, see the documentation of rclcpp::Node::create_client.

Parameters
nodeROS node handler.
addressName of the service.
qosQOS Communication quality of service profile.

◆ ServiceServerHandler() [2/4]

template<class ServiceType >
mrs_lib::ServiceServerHandler< ServiceType >::ServiceServerHandler ( )

Default constructor to avoid having to use pointers.

It does nothing and the object it constructs will also do nothing. Use some of the other constructors for a construction of an actually usable object.

◆ ServiceServerHandler() [3/4]

template<class ServiceType >
mrs_lib::ServiceServerHandler< ServiceType >::ServiceServerHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const callback_t &  cbk,
const rclcpp::QoS &  qos,
const rclcpp::CallbackGroup::SharedPtr &  callback_group 
)

A convenience constructor.

This is just for convenience when you want to specify the callback group.

Parameters
nodeROS node handler.
addressName of the service.
qosQOS Communication quality of service profile.
callback_groupCallback group used internally by the node for the response callback. Set to nullptr to use the default one.

◆ ServiceServerHandler() [4/4]

template<class ServiceType >
mrs_lib::ServiceServerHandler< ServiceType >::ServiceServerHandler ( rclcpp::Node::SharedPtr &  node,
const std::string &  address,
const callback_t &  cbk,
const rclcpp::CallbackGroup::SharedPtr &  callback_group 
)

A convenience constructor.

This is just for convenience when you want to specify the callback group but don't care about QoS.

Parameters
nodeROS node handler.
addressName of the service.
callback_groupCallback group used internally by the node for the response callback. Set to nullptr to use the default one.

The documentation for this class was generated from the following files: