#include <client.hpp>
|
| Client (rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, const std::string &service_name, rcl_client_options_t &client_options) |
|
virtual | ~Client () |
|
std::shared_ptr< void > | create_response () |
|
std::shared_ptr< rmw_request_id_t > | create_request_header () |
|
void | handle_response (std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response) |
|
SharedFuture | async_send_request (SharedRequest request) |
|
template<typename CallbackT , typename std::enable_if< rclcpp::function_traits::same_arguments< CallbackT, CallbackType >::value >::type * = nullptr> |
SharedFuture | async_send_request (SharedRequest request, CallbackT &&cb) |
|
template<typename CallbackT , typename std::enable_if< rclcpp::function_traits::same_arguments< CallbackT, CallbackWithRequestType >::value >::type * = nullptr> |
SharedFutureWithRequest | async_send_request (SharedRequest request, CallbackT &&cb) |
|
| ClientBase (rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, const std::string &service_name) |
|
virtual | ~ClientBase () |
|
const std::string & | get_service_name () const |
|
const rcl_client_t * | get_client_handle () const |
|
bool | service_is_ready () const |
|
template<typename RatioT = std::milli> |
bool | wait_for_service (std::chrono::duration< int64_t, RatioT > timeout=std::chrono::duration< int64_t, RatioT >(-1)) |
|
§ SharedRequest
template<typename ServiceT>
§ SharedResponse
template<typename ServiceT>
§ Promise
template<typename ServiceT>
§ PromiseWithRequest
template<typename ServiceT>
§ SharedPromise
template<typename ServiceT>
§ SharedPromiseWithRequest
template<typename ServiceT>
§ SharedFuture
template<typename ServiceT>
§ SharedFutureWithRequest
template<typename ServiceT>
§ CallbackType
template<typename ServiceT>
§ CallbackWithRequestType
template<typename ServiceT>
§ Client()
template<typename ServiceT>
§ ~Client()
template<typename ServiceT>
§ create_response()
template<typename ServiceT>
§ create_request_header()
template<typename ServiceT>
§ handle_response()
template<typename ServiceT>
§ async_send_request() [1/3]
template<typename ServiceT>
§ async_send_request() [2/3]
template<typename ServiceT>
template<typename CallbackT , typename std::enable_if< rclcpp::function_traits::same_arguments< CallbackT, CallbackType >::value >::type * = nullptr>
§ async_send_request() [3/3]
template<typename ServiceT>
template<typename CallbackT , typename std::enable_if< rclcpp::function_traits::same_arguments< CallbackT, CallbackWithRequestType >::value >::type * = nullptr>
The documentation for this class was generated from the following file: