Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Attributes | List of all members
nav2_util::ServiceClient< ServiceT, NodeT > Class Template Reference

A simple wrapper on ROS2 services client. More...

#include <nav2_util/include/nav2_util/service_client.hpp>

Collaboration diagram for nav2_util::ServiceClient< ServiceT, NodeT >:
Collaboration graph
[legend]

Public Types

using RequestType = typename ServiceT::Request
 
using ResponseType = typename ServiceT::Response
 
using SharedPtr = std::shared_ptr< ServiceClient< ServiceT, NodeT > >
 

Public Member Functions

 ServiceClient (const std::string &service_name, const NodeT &provided_node, bool use_internal_executor=false)
 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...
 
std::shared_future< typename ResponseType::SharedPtr > async_call (typename RequestType::SharedPtr &request)
 Asynchronously call the service. More...
 
template<typename CallbackT >
void async_call (typename RequestType::SharedPtr request, CallbackT &&callback)
 Asynchronously call the service with a callback. More...
 
bool wait_for_service (const std::chrono::nanoseconds timeout=std::chrono::nanoseconds::max())
 Block until a service is available or timeout. More...
 
template<typename FutureT >
rclcpp::FutureReturnCode spin_until_complete (const FutureT &future, const std::chrono::nanoseconds timeout=std::chrono::nanoseconds(-1))
 Spins the executor until the provided future is complete or the timeout is reached. More...
 
std::string getServiceName ()
 Gets the service name. More...
 

Protected Attributes

std::string service_name_
 
NodeT node_
 
rclcpp::CallbackGroup::SharedPtr callback_group_ {nullptr}
 
rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_
 
rclcpp::Client< ServiceT >::SharedPtr client_
 
bool use_internal_executor_
 

Detailed Description

template<class ServiceT, typename NodeT = rclcpp::Node::SharedPtr>
class nav2_util::ServiceClient< ServiceT, NodeT >

A simple wrapper on ROS2 services client.

Definition at line 31 of file service_client.hpp.

Constructor & Destructor Documentation

◆ ServiceClient()

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
nav2_util::ServiceClient< ServiceT, NodeT >::ServiceClient ( const std::string &  service_name,
const NodeT &  provided_node,
bool  use_internal_executor = false 
)
inlineexplicit

A constructor.

Parameters
service_namename of the service to call
provided_nodeNode to create the service client off of
use_internal_executorWhether to create an internal executor or not

Definition at line 40 of file service_client.hpp.

Member Function Documentation

◆ async_call() [1/2]

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
std::shared_future<typename ResponseType::SharedPtr> nav2_util::ServiceClient< ServiceT, NodeT >::async_call ( typename RequestType::SharedPtr &  request)
inline

Asynchronously call the service.

Parameters
requestThe request object to call the service using
Returns
std::shared_future<typename ResponseType::SharedPtr> The shared future of the service response

Definition at line 150 of file service_client.hpp.

◆ async_call() [2/2]

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
template<typename CallbackT >
void nav2_util::ServiceClient< ServiceT, NodeT >::async_call ( typename RequestType::SharedPtr  request,
CallbackT &&  callback 
)
inline

Asynchronously call the service with a callback.

Parameters
requestThe request object to call the service using
callbackThe callback to call when the service response is received

Definition at line 164 of file service_client.hpp.

◆ getServiceName()

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
std::string nav2_util::ServiceClient< ServiceT, NodeT >::getServiceName ( )
inline

Gets the service name.

Returns
string Service name

Definition at line 202 of file service_client.hpp.

◆ invoke() [1/2]

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
ResponseType::SharedPtr nav2_util::ServiceClient< ServiceT, NodeT >::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
requestThe request object to call the service using
timeoutMaximum timeout to wait for, default infinite
Returns
Response A pointer to the service response from the request

Definition at line 84 of file service_client.hpp.

References nav2_util::ServiceClient< ServiceT, NodeT >::spin_until_complete().

Referenced by nav2_lifecycle_manager::LifecycleManagerClient::callService(), and nav2_behavior_tree::IsPathValidCondition::tick().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ invoke() [2/2]

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
bool nav2_util::ServiceClient< ServiceT, NodeT >::invoke ( typename RequestType::SharedPtr &  request,
typename ResponseType::SharedPtr &  response 
)
inline

Invoke the service and block until completed.

Parameters
requestThe request object to call the service using
ResponseA pointer to the service response from the request
Returns
bool Whether it was successfully called

Definition at line 117 of file service_client.hpp.

References nav2_util::ServiceClient< ServiceT, NodeT >::spin_until_complete().

Here is the call graph for this function:

◆ spin_until_complete()

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
template<typename FutureT >
rclcpp::FutureReturnCode nav2_util::ServiceClient< ServiceT, NodeT >::spin_until_complete ( const FutureT &  future,
const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds(-1) 
)
inline

Spins the executor until the provided future is complete or the timeout is reached.

Parameters
futureThe shared future to wait for completion.
timeoutThe maximum time to wait for the future to complete. Default is -1 (no timeout).
Returns
rclcpp::FutureReturnCode indicating the result of the spin operation.

Definition at line 187 of file service_client.hpp.

Referenced by nav2_util::ServiceClient< ServiceT, NodeT >::invoke().

Here is the caller graph for this function:

◆ wait_for_service()

template<class ServiceT , typename NodeT = rclcpp::Node::SharedPtr>
bool nav2_util::ServiceClient< ServiceT, NodeT >::wait_for_service ( const std::chrono::nanoseconds  timeout = std::chrono::nanoseconds::max())
inline

Block until a service is available or timeout.

Parameters
timeoutMaximum timeout to wait for, default infinite
Returns
bool true if service is available

Definition at line 174 of file service_client.hpp.

Referenced by nav2_lifecycle_manager::LifecycleManagerClient::callService(), and nav2_lifecycle_manager::LifecycleManagerClient::is_active().

Here is the caller graph for this function:

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