#include <generic_client.hpp>

Public Types | |
| using | CallbackType = std::function< void(SharedFuture)> |
| using | CallbackWithRequestType = std::function< void(SharedFutureWithRequest)> |
| using | Promise = std::promise< SharedResponse > |
| using | PromiseWithRequest = std::promise< std::pair< SharedRequest, SharedResponse > > |
| using | SharedFuture = std::shared_future< SharedResponse > |
| using | SharedFutureWithRequest = std::shared_future< std::pair< SharedRequest, SharedResponse > > |
| using | SharedPromise = std::shared_ptr< Promise > |
| using | SharedPromiseWithRequest = std::shared_ptr< PromiseWithRequest > |
| using | SharedRequest = std::shared_ptr< rclcpp::SerializedMessage > |
| using | SharedResponse = std::shared_ptr< rclcpp::SerializedMessage > |
Public Member Functions | |
| SharedFuture | async_send_request (SharedRequest request) |
| SharedFuture | async_send_request (SharedRequest request, CallbackType &&cb) |
| std::shared_ptr< rmw_request_id_t > | create_request_header () override |
| std::shared_ptr< void > | create_response () override |
| GenericClient (rclcpp::node_interfaces::NodeBaseInterface *node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, std::string service_name, std::string service_type, rcl_client_options_t &client_options) | |
| void | handle_response (std::shared_ptr< rmw_request_id_t > request_header, std::shared_ptr< void > response) override |
| virtual | ~GenericClient () |
Private Attributes | |
| const rosidl_message_type_support_t * | _requestTypeSupportHdl |
| const rosidl_message_type_support_t * | _responseTypeSupportHdl |
| const rosidl_service_type_support_t * | _serviceTypeSupportHdl |
| const rosidl_service_type_support_t * | _typeIntrospectionHdl |
| std::shared_ptr< rcpputils::SharedLibrary > | _typeIntrospectionLib |
| std::shared_ptr< rcpputils::SharedLibrary > | _typeSupportLib |
| std::map< int64_t, std::tuple< SharedPromise, CallbackType, SharedFuture > > | pending_requests_ |
| std::mutex | pending_requests_mutex_ |
Definition at line 11 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::CallbackType = std::function<void(SharedFuture)> |
Definition at line 21 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::CallbackWithRequestType = std::function<void(SharedFutureWithRequest)> |
Definition at line 22 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::Promise = std::promise<SharedResponse> |
Definition at line 15 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::PromiseWithRequest = std::promise<std::pair<SharedRequest, SharedResponse> > |
Definition at line 16 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedFuture = std::shared_future<SharedResponse> |
Definition at line 19 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedFutureWithRequest = std::shared_future<std::pair<SharedRequest, SharedResponse> > |
Definition at line 20 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedPromise = std::shared_ptr<Promise> |
Definition at line 17 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedPromiseWithRequest = std::shared_ptr<PromiseWithRequest> |
Definition at line 18 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedRequest = std::shared_ptr<rclcpp::SerializedMessage> |
Definition at line 13 of file generic_client.hpp.
| using foxglove_bridge::GenericClient::SharedResponse = std::shared_ptr<rclcpp::SerializedMessage> |
Definition at line 14 of file generic_client.hpp.
| foxglove_bridge::GenericClient::GenericClient | ( | rclcpp::node_interfaces::NodeBaseInterface * | node_base, |
| rclcpp::node_interfaces::NodeGraphInterface::SharedPtr | node_graph, | ||
| std::string | service_name, | ||
| std::string | service_type, | ||
| rcl_client_options_t & | client_options | ||
| ) |
Definition at line 95 of file generic_client.cpp.
|
inlinevirtual |
Definition at line 30 of file generic_client.hpp.
| GenericClient::SharedFuture foxglove_bridge::GenericClient::async_send_request | ( | SharedRequest | request | ) |
Definition at line 194 of file generic_client.cpp.
| GenericClient::SharedFuture foxglove_bridge::GenericClient::async_send_request | ( | SharedRequest | request, |
| CallbackType && | cb | ||
| ) |
Definition at line 198 of file generic_client.cpp.
|
override |
Definition at line 160 of file generic_client.cpp.
|
override |
Definition at line 155 of file generic_client.cpp.
|
override |
Definition at line 164 of file generic_client.cpp.
|
private |
Definition at line 47 of file generic_client.hpp.
|
private |
Definition at line 48 of file generic_client.hpp.
|
private |
Definition at line 46 of file generic_client.hpp.
|
private |
Definition at line 49 of file generic_client.hpp.
|
private |
Definition at line 45 of file generic_client.hpp.
|
private |
Definition at line 44 of file generic_client.hpp.
|
private |
Definition at line 42 of file generic_client.hpp.
|
private |
Definition at line 43 of file generic_client.hpp.