A simple wrapper on ROS2 services for invoke() and block-style calling.
More...
#include <nav2_util/include/nav2_util/service_client.hpp>
|
using | RequestType = typename ServiceT::Request |
|
using | ResponseType = typename ServiceT::Response |
|
|
| ServiceClient (const std::string &service_name, const rclcpp::Node::SharedPtr &provided_node) |
| A constructor. More...
|
|
ResponseType::SharedPtr | invoke (typename RequestType::SharedPtr &request, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1)) |
| Invoke the service and block until completed or timed out. More...
|
|
bool | invoke (typename RequestType::SharedPtr &request, typename ResponseType::SharedPtr &response) |
| Invoke the service and block until completed. More...
|
|
bool | wait_for_service (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max()) |
| Block until a service is available or timeout. More...
|
|
std::string | getServiceName () |
| Gets the service name. More...
|
|
|
std::string | service_name_ |
|
rclcpp::Node::SharedPtr | node_ |
|
rclcpp::CallbackGroup::SharedPtr | callback_group_ |
|
rclcpp::executors::SingleThreadedExecutor | callback_group_executor_ |
|
rclcpp::Client< ServiceT >::SharedPtr | client_ |
|
template<class ServiceT>
class nav2_util::ServiceClient< ServiceT >
A simple wrapper on ROS2 services for invoke() and block-style calling.
Definition at line 30 of file service_client.hpp.
◆ ServiceClient()
template<class ServiceT >
A constructor.
- Parameters
-
service_name | name of the service to call |
provided_node | Node to create the service client off of |
Definition at line 38 of file service_client.hpp.
◆ getServiceName()
template<class ServiceT >
◆ invoke() [1/2]
template<class ServiceT >
ResponseType::SharedPtr nav2_util::ServiceClient< ServiceT >::invoke |
( |
typename RequestType::SharedPtr & |
request, |
|
|
const std::chrono::nanoseconds |
timeout = std::chrono::nanoseconds(-1) |
|
) |
| |
|
inline |
Invoke the service and block until completed or timed out.
- Parameters
-
request | The request object to call the service using |
timeout | Maximum timeout to wait for, default infinite |
- Returns
- Response A pointer to the service response from the request
Definition at line 62 of file service_client.hpp.
◆ invoke() [2/2]
template<class ServiceT >
bool nav2_util::ServiceClient< ServiceT >::invoke |
( |
typename RequestType::SharedPtr & |
request, |
|
|
typename ResponseType::SharedPtr & |
response |
|
) |
| |
|
inline |
Invoke the service and block until completed.
- Parameters
-
request | The request object to call the service using |
Response | A pointer to the service response from the request |
- Returns
- bool Whether it was successfully called
Definition at line 98 of file service_client.hpp.
◆ wait_for_service()
template<class ServiceT >
bool nav2_util::ServiceClient< ServiceT >::wait_for_service |
( |
const std::chrono::nanoseconds |
timeout = std::chrono::nanoseconds::max() | ) |
|
|
inline |
Block until a service is available or timeout.
- Parameters
-
timeout | Maximum timeout to wait for, default infinite |
- Returns
- bool true if service is available
Definition at line 134 of file service_client.hpp.
The documentation for this class was generated from the following file: