Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
A simple wrapper on ROS2 services client. More...
#include <nav2_util/include/nav2_util/service_client.hpp>
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... | |
A simple wrapper on ROS2 services client.
Definition at line 31 of file service_client.hpp.
|
inlineexplicit |
A constructor.
service_name | name of the service to call |
provided_node | Node to create the service client off of |
use_internal_executor | Whether to create an internal executor or not |
Definition at line 40 of file service_client.hpp.
|
inline |
Asynchronously call the service.
request | The request object to call the service using |
Definition at line 150 of file service_client.hpp.
|
inline |
Asynchronously call the service with a callback.
request | The request object to call the service using |
callback | The callback to call when the service response is received |
Definition at line 164 of file service_client.hpp.
|
inline |
Gets the service name.
Definition at line 202 of file service_client.hpp.
|
inline |
Invoke the service and block until completed or timed out.
request | The request object to call the service using |
timeout | Maximum timeout to wait for, default infinite |
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().
|
inline |
Invoke the service and block until completed.
request | The request object to call the service using |
Response | A pointer to the service response from the request |
Definition at line 117 of file service_client.hpp.
References nav2_util::ServiceClient< ServiceT, NodeT >::spin_until_complete().
|
inline |
Spins the executor until the provided future is complete or the timeout is reached.
future | The shared future to wait for completion. |
timeout | The maximum time to wait for the future to complete. Default is -1 (no timeout). |
Definition at line 187 of file service_client.hpp.
Referenced by nav2_util::ServiceClient< ServiceT, NodeT >::invoke().
|
inline |
Block until a service is available or timeout.
timeout | Maximum timeout to wait for, default infinite |
Definition at line 174 of file service_client.hpp.
Referenced by nav2_lifecycle_manager::LifecycleManagerClient::callService(), and nav2_lifecycle_manager::LifecycleManagerClient::is_active().