![]() |
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
user wrapper of the service client handler implementation More...
#include <service_client_handler.h>
Classes | |
| class | Impl |
| implementation of the service client handler More... | |
Public Member Functions | |
| ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::QoS &qos=rclcpp::ServicesQoS()) | |
| The main constructor with all the options. | |
| ServiceClientHandler () | |
| Default constructor to avoid having to use pointers. | |
| ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::QoS &qos, const rclcpp::CallbackGroup::SharedPtr &callback_group) | |
| A convenience constructor. | |
| ServiceClientHandler (rclcpp::Node::SharedPtr &node, const std::string &address, const rclcpp::CallbackGroup::SharedPtr &callback_group) | |
| A convenience constructor. | |
| std::optional< std::shared_ptr< typename ServiceType::Response > > | callSync (const std::shared_ptr< typename ServiceType::Request > &request) |
| Synchronous (blocking) call of the service. | |
| std::optional< std::shared_future< std::shared_ptr< typename ServiceType::Response > > > | callAsync (const std::shared_ptr< typename ServiceType::Request > &request) |
| Asynchronous (non-blocking) call of the service. | |
user wrapper of the service client handler implementation
| mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | rclcpp::Node::SharedPtr & | node, |
| const std::string & | address, | ||
| 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.
| node | ROS node handler. |
| address | Name of the service. |
| qos | QOS Communication quality of service profile. |
| mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | ) |
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.
| mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | rclcpp::Node::SharedPtr & | node, |
| const std::string & | address, | ||
| 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.
| node | ROS node handler. |
| address | Name of the service. |
| qos | QOS Communication quality of service profile. |
| callback_group | Callback group used internally by the node for the response callback. Set to nullptr to use the default one. |
| mrs_lib::ServiceClientHandler< ServiceType >::ServiceClientHandler | ( | rclcpp::Node::SharedPtr & | node, |
| const std::string & | address, | ||
| 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.
| node | ROS node handler. |
| address | Name of the service. |
| callback_group | Callback group used internally by the node for the response callback. Set to nullptr to use the default one. |
| std::optional< std::shared_future< std::shared_ptr< typename ServiceType::Response > > > mrs_lib::ServiceClientHandler< ServiceType >::callAsync | ( | const std::shared_ptr< typename ServiceType::Request > & | request | ) |
Asynchronous (non-blocking) call of the service.
| request | The service request to be sent with the call |
| std::optional< std::shared_ptr< typename ServiceType::Response > > mrs_lib::ServiceClientHandler< ServiceType >::callSync | ( | const std::shared_ptr< typename ServiceType::Request > & | request | ) |
Synchronous (blocking) call of the service.
This method will block until the service call returns.
| request | The service request to be sent with the call |