|
SMACC2
|
Generic ROS2 service client component for SMACC2. More...
#include <cp_service_client.hpp>


Public Types | |
| using | Client = rclcpp::Client<ServiceType> |
| using | Request = typename ServiceType::Request |
| using | Response = typename ServiceType::Response |
| using | SharedRequest = typename Request::SharedPtr |
| using | SharedResponse = typename Response::SharedPtr |
| using | SharedFuture = typename rclcpp::Client<ServiceType>::SharedFuture |
Public Member Functions | |
| CpServiceClient ()=default | |
| Default constructor. | |
| CpServiceClient (const std::string &serviceName) | |
| Constructor with service name. | |
| CpServiceClient (const std::string &serviceName, std::chrono::milliseconds serviceTimeout) | |
| Constructor with service name and timeout. | |
| virtual | ~CpServiceClient ()=default |
| SharedFuture | sendRequest (SharedRequest request) |
| Send a service request asynchronously. | |
| SharedResponse | sendRequestSync (SharedRequest request) |
| Send a service request synchronously (blocking) | |
| bool | isServiceReady () const |
| Check if the service server is ready. | |
| void | waitForService () |
| Wait for the service to become available. | |
| void | onInitialize () override |
| Component initialization - creates the ROS2 service client. | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onComponentInitialization () |
| Configure event posting with proper template parameters. | |
| template<typename T > | |
| boost::signals2::connection | onResponse (void(T::*callback)(const SharedResponse &), T *object) |
| Helper method to connect a callback to the response signal. | |
| template<typename T > | |
| boost::signals2::connection | onRequestSent (void(T::*callback)(), T *object) |
| Helper method to connect a callback to the request sent signal. | |
| template<typename T > | |
| boost::signals2::connection | onFailure (void(T::*callback)(), T *object) |
| Helper method to connect a callback to the failure signal. | |
| std::shared_ptr< Client > | getServiceClient () const |
| Get the underlying ROS2 service client. | |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Public Attributes | |
| std::optional< std::string > | serviceName |
| std::optional< std::chrono::milliseconds > | serviceTimeout |
| smacc2::SmaccSignal< void(const SharedResponse &)> | onServiceResponse_ |
| smacc2::SmaccSignal< void()> | onServiceRequestSent_ |
| smacc2::SmaccSignal< void()> | onServiceFailure_ |
| std::function< void(const SharedResponse &)> | postResponseEvent |
| std::function< void()> | postRequestSentEvent |
| std::function< void()> | postFailureEvent |
Private Attributes | |
| std::shared_ptr< Client > | client_ = nullptr |
| std::optional< SharedFuture > | lastRequest_ |
| std::mutex | serviceMutex_ |
Additional Inherited Members | |
Protected Member Functions inherited from smacc2::ISmaccComponent | |
| template<typename TOrthogonal , typename TClient > | |
| void | onComponentInitialization () |
| template<typename EventType > | |
| void | postEvent (const EventType &ev) |
| template<typename EventType > | |
| void | postEvent () |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| template<typename TComponent > | |
| void | requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TComponent > | |
| void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
| template<typename TClient > | |
| void | requiresClient (TClient *&requiredClientStorage) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingComponent (TArgs... targs) |
| template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
| SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
| rclcpp::Node::SharedPtr | getNode () |
| rclcpp::Logger | getLogger () const |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Generic ROS2 service client component for SMACC2.
CpServiceClient provides a reusable service client component that can be used by any SMACC2 client library requiring ROS2 service communication. It follows the same pattern as CpActionClient, providing signals, event posting, and thread-safe service call management.
Key Features:
Usage Example:
| ServiceType | ROS2 service type (e.g., std_srvs::srv::SetBool) |
Definition at line 67 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::Client = rclcpp::Client<ServiceType> |
Definition at line 71 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::Request = typename ServiceType::Request |
Definition at line 72 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::Response = typename ServiceType::Response |
Definition at line 73 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedFuture = typename rclcpp::Client<ServiceType>::SharedFuture |
Definition at line 76 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedRequest = typename Request::SharedPtr |
Definition at line 74 of file cp_service_client.hpp.
| using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedResponse = typename Response::SharedPtr |
Definition at line 75 of file cp_service_client.hpp.
|
default |
Default constructor.
|
inline |
Constructor with service name.
| serviceName | ROS2 service name (e.g., "/my_node/my_service") |
Definition at line 105 of file cp_service_client.hpp.
|
inline |
Constructor with service name and timeout.
| serviceName | ROS2 service name |
| serviceTimeout | Maximum time to wait for service response |
Definition at line 112 of file cp_service_client.hpp.
|
virtualdefault |
|
inline |
Get the underlying ROS2 service client.
Provides access to the raw rclcpp::Client for advanced usage scenarios.
Definition at line 370 of file cp_service_client.hpp.
References smacc2::client_core_components::CpServiceClient< ServiceType >::client_.
|
inline |
Check if the service server is ready.
Definition at line 223 of file cp_service_client.hpp.
References smacc2::client_core_components::CpServiceClient< ServiceType >::client_.
|
inline |
Configure event posting with proper template parameters.
This method is called during component allocation to set up the event posting lambdas with the correct orthogonal and source object types. This enables type-safe event posting to the state machine.
| TOrthogonal | The orthogonal type that owns this component |
| TSourceObject | The source object type (typically the client) |
Definition at line 292 of file cp_service_client.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::postEvent(), smacc2::client_core_components::CpServiceClient< ServiceType >::postFailureEvent, smacc2::client_core_components::CpServiceClient< ServiceType >::postRequestSentEvent, and smacc2::client_core_components::CpServiceClient< ServiceType >::postResponseEvent.

|
inline |
Helper method to connect a callback to the failure signal.
| T | Type of the callback object |
| callback | Member function pointer to call on failure |
| object | Object instance that owns the callback |
Definition at line 358 of file cp_service_client.hpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

|
inlineoverridevirtual |
Component initialization - creates the ROS2 service client.
Called by SMACC2 framework during component initialization. Creates the underlying rclcpp::Client for the specified service.
Reimplemented from smacc2::ISmaccComponent.
Definition at line 263 of file cp_service_client.hpp.
References smacc2::client_core_components::CpServiceClient< ServiceType >::client_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::ISmaccComponent::getNode(), and smacc2::client_core_components::CpServiceClient< ServiceType >::serviceName.

|
inline |
Helper method to connect a callback to the request sent signal.
| T | Type of the callback object |
| callback | Member function pointer to call when request is sent |
| object | Object instance that owns the callback |
Definition at line 344 of file cp_service_client.hpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

|
inline |
Helper method to connect a callback to the response signal.
Provides a convenient way to connect member functions to the service response signal with proper lifetime management.
| T | Type of the callback object |
| callback | Member function pointer to call on response |
| object | Object instance that owns the callback |
Definition at line 330 of file cp_service_client.hpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

|
inline |
Send a service request asynchronously.
Sends a service request and returns a future. The caller can wait on the future or let the component handle the response via signals/events.
| request | Shared pointer to the service request |
Definition at line 128 of file cp_service_client.hpp.
References smacc2::client_core_components::CpServiceClient< ServiceType >::client_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpServiceClient< ServiceType >::lastRequest_, smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceRequestSent_, smacc2::client_core_components::CpServiceClient< ServiceType >::postRequestSentEvent, and smacc2::client_core_components::CpServiceClient< ServiceType >::serviceMutex_.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync().


|
inline |
Send a service request synchronously (blocking)
Sends a service request and blocks until the response is received or a timeout occurs. This is a convenience method that wraps sendRequest() with a blocking wait.
| request | Shared pointer to the service request |
| std::runtime_error | if service call fails or times out |
Definition at line 170 of file cp_service_client.hpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceFailure_, smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceResponse_, smacc2::client_core_components::CpServiceClient< ServiceType >::postFailureEvent, smacc2::client_core_components::CpServiceClient< ServiceType >::postResponseEvent, smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest(), and smacc2::client_core_components::CpServiceClient< ServiceType >::serviceTimeout.

|
inline |
Wait for the service to become available.
Blocks until the service server is ready to accept requests. Uses a default timeout or the configured serviceTimeout.
Definition at line 231 of file cp_service_client.hpp.
References smacc2::client_core_components::CpServiceClient< ServiceType >::client_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and smacc2::client_core_components::CpServiceClient< ServiceType >::serviceTimeout.

|
private |
Definition at line 373 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::getServiceClient(), smacc2::client_core_components::CpServiceClient< ServiceType >::isServiceReady(), smacc2::client_core_components::CpServiceClient< ServiceType >::onInitialize(), smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest(), and smacc2::client_core_components::CpServiceClient< ServiceType >::waitForService().
|
private |
Definition at line 374 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest().
| smacc2::SmaccSignal<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceFailure_ |
Definition at line 87 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync().
| smacc2::SmaccSignal<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceRequestSent_ |
Definition at line 86 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest().
| smacc2::SmaccSignal<void(const SharedResponse &)> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceResponse_ |
Definition at line 85 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync().
| std::function<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::postFailureEvent |
Definition at line 94 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::onComponentInitialization(), and smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync().
| std::function<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::postRequestSentEvent |
Definition at line 93 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::onComponentInitialization(), and smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest().
| std::function<void(const SharedResponse &)> smacc2::client_core_components::CpServiceClient< ServiceType >::postResponseEvent |
Definition at line 92 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::onComponentInitialization(), and smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync().
|
private |
Definition at line 375 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest().
| std::optional<std::string> smacc2::client_core_components::CpServiceClient< ServiceType >::serviceName |
Definition at line 79 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::onInitialize().
| std::optional<std::chrono::milliseconds> smacc2::client_core_components::CpServiceClient< ServiceType >::serviceTimeout |
Definition at line 80 of file cp_service_client.hpp.
Referenced by smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync(), and smacc2::client_core_components::CpServiceClient< ServiceType >::waitForService().