Template Class CpServiceClient

Inheritance Relationships

Base Type

Class Documentation

template<typename ServiceType>
class CpServiceClient : public smacc2::ISmaccComponent

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:

  • Template-based for type safety with any ROS2 service type

  • SMACC2 signal integration for event-driven responses

  • Automatic SMACC2 event posting via template configuration

  • Both synchronous and asynchronous service call support

  • Thread-safe service call execution

  • Service availability checking and waiting

Usage Example:

// In your client's onInitialize():
auto serviceClient = this->createComponent<
  smacc2::client_core_components::CpServiceClient<my_msgs::srv::MyService>>(
  "/my_service_name");

// Send a request:
auto request = std::make_shared<my_msgs::srv::MyService::Request>();
request->data = 42;
serviceClient->sendRequestSync(request);

Template Parameters:

ServiceType – ROS2 service type (e.g., std_srvs::srv::SetBool)

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 Functions

CpServiceClient() = default

Default constructor.

inline CpServiceClient(const std::string &serviceName)

Constructor with service name.

Parameters:

serviceName – ROS2 service name (e.g., “/my_node/my_service”)

inline CpServiceClient(const std::string &serviceName, std::chrono::milliseconds serviceTimeout)

Constructor with service name and timeout.

Parameters:
  • serviceName – ROS2 service name

  • serviceTimeout – Maximum time to wait for service response

virtual ~CpServiceClient() = default
inline SharedFuture sendRequest(SharedRequest request)

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.

Parameters:

request – Shared pointer to the service request

Returns:

SharedFuture Future for the service response

inline SharedResponse sendRequestSync(SharedRequest request)

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.

Parameters:

request – Shared pointer to the service request

Throws:

std::runtime_error – if service call fails or times out

Returns:

SharedResponse Response from the service

inline bool isServiceReady() const

Check if the service server is ready.

Returns:

true if service is available, false otherwise

inline void waitForService()

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.

inline virtual void onInitialize() override

Component initialization - creates the ROS2 service client.

Called by SMACC2 framework during component initialization. Creates the underlying rclcpp::Client for the specified service.

template<typename TOrthogonal, typename TSourceObject>
inline void onComponentInitialization()

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.

Template Parameters:
  • TOrthogonal – The orthogonal type that owns this component

  • TSourceObject – The source object type (typically the client)

template<typename T>
inline smacc2::SmaccSignalConnection onResponse(void (T::* callback)(const SharedResponse&), T *object)

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.

Template Parameters:

T – Type of the callback object

Parameters:
  • callback – Member function pointer to call on response

  • object – Object instance that owns the callback

Returns:

Signal connection handle

template<typename T>
inline smacc2::SmaccSignalConnection onRequestSent(void (T::* callback)(), T *object)

Helper method to connect a callback to the request sent signal.

Template Parameters:

T – Type of the callback object

Parameters:
  • callback – Member function pointer to call when request is sent

  • object – Object instance that owns the callback

Returns:

Signal connection handle

template<typename T>
inline smacc2::SmaccSignalConnection onFailure(void (T::* callback)(), T *object)

Helper method to connect a callback to the failure signal.

Template Parameters:

T – Type of the callback object

Parameters:
  • callback – Member function pointer to call on failure

  • object – Object instance that owns the callback

Returns:

Signal connection handle

inline std::shared_ptr<Client> getServiceClient() const

Get the underlying ROS2 service client.

Provides access to the raw rclcpp::Client for advanced usage scenarios.

Returns:

Shared pointer to the rclcpp service client

Public Members

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