SMACC2
Loading...
Searching...
No Matches
smacc2::client_core_components::CpServiceClient< ServiceType > Class Template Reference

Generic ROS2 service client component for SMACC2. More...

#include <cp_service_client.hpp>

Inheritance diagram for smacc2::client_core_components::CpServiceClient< ServiceType >:
Inheritance graph
Collaboration diagram for smacc2::client_core_components::CpServiceClient< ServiceType >:
Collaboration graph

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< ClientgetServiceClient () 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< Clientclient_ = nullptr
 
std::optional< SharedFuturelastRequest_
 
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
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

template<typename ServiceType>
class smacc2::client_core_components::CpServiceClient< ServiceType >

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<
"/my_service_name");
// Send a request:
auto request = std::make_shared<my_msgs::srv::MyService::Request>();
request->data = 42;
serviceClient->sendRequestSync(request);
Generic ROS2 service client component for SMACC2.
Template Parameters
ServiceTypeROS2 service type (e.g., std_srvs::srv::SetBool)

Definition at line 67 of file cp_service_client.hpp.

Member Typedef Documentation

◆ Client

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::Client = rclcpp::Client<ServiceType>

Definition at line 71 of file cp_service_client.hpp.

◆ Request

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::Request = typename ServiceType::Request

Definition at line 72 of file cp_service_client.hpp.

◆ Response

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::Response = typename ServiceType::Response

Definition at line 73 of file cp_service_client.hpp.

◆ SharedFuture

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedFuture = typename rclcpp::Client<ServiceType>::SharedFuture

Definition at line 76 of file cp_service_client.hpp.

◆ SharedRequest

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedRequest = typename Request::SharedPtr

Definition at line 74 of file cp_service_client.hpp.

◆ SharedResponse

template<typename ServiceType >
using smacc2::client_core_components::CpServiceClient< ServiceType >::SharedResponse = typename Response::SharedPtr

Definition at line 75 of file cp_service_client.hpp.

Constructor & Destructor Documentation

◆ CpServiceClient() [1/3]

template<typename ServiceType >
smacc2::client_core_components::CpServiceClient< ServiceType >::CpServiceClient ( )
default

Default constructor.

◆ CpServiceClient() [2/3]

template<typename ServiceType >
smacc2::client_core_components::CpServiceClient< ServiceType >::CpServiceClient ( const std::string & serviceName)
inline

Constructor with service name.

Parameters
serviceNameROS2 service name (e.g., "/my_node/my_service")

Definition at line 105 of file cp_service_client.hpp.

◆ CpServiceClient() [3/3]

template<typename ServiceType >
smacc2::client_core_components::CpServiceClient< ServiceType >::CpServiceClient ( const std::string & serviceName,
std::chrono::milliseconds serviceTimeout )
inline

Constructor with service name and timeout.

Parameters
serviceNameROS2 service name
serviceTimeoutMaximum time to wait for service response

Definition at line 112 of file cp_service_client.hpp.

114 {
115 }
std::optional< std::chrono::milliseconds > serviceTimeout

◆ ~CpServiceClient()

template<typename ServiceType >
virtual smacc2::client_core_components::CpServiceClient< ServiceType >::~CpServiceClient ( )
virtualdefault

Member Function Documentation

◆ getServiceClient()

template<typename ServiceType >
std::shared_ptr< Client > smacc2::client_core_components::CpServiceClient< ServiceType >::getServiceClient ( ) const
inline

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

Definition at line 370 of file cp_service_client.hpp.

370{ return client_; }

References smacc2::client_core_components::CpServiceClient< ServiceType >::client_.

◆ isServiceReady()

template<typename ServiceType >
bool smacc2::client_core_components::CpServiceClient< ServiceType >::isServiceReady ( ) const
inline

Check if the service server is ready.

Returns
true if service is available, false otherwise

Definition at line 223 of file cp_service_client.hpp.

223{ return client_ && client_->service_is_ready(); }

References smacc2::client_core_components::CpServiceClient< ServiceType >::client_.

◆ onComponentInitialization()

template<typename ServiceType >
template<typename TOrthogonal , typename TSourceObject >
void smacc2::client_core_components::CpServiceClient< ServiceType >::onComponentInitialization ( )
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.

Template Parameters
TOrthogonalThe orthogonal type that owns this component
TSourceObjectThe source object type (typically the client)

Definition at line 292 of file cp_service_client.hpp.

293 {
294 // Set up event posting functions with proper template parameters
295 postResponseEvent = [this](const SharedResponse & response)
296 {
297 auto * ev = new EvServiceResponse<TSourceObject, TOrthogonal, Response>();
298 ev->response = *response;
299 this->postEvent(ev);
300 RCLCPP_DEBUG(getLogger(), "[%s] SERVICE RESPONSE EVENT", this->getName().c_str());
301 };
302
303 postRequestSentEvent = [this]()
304 {
305 auto * ev = new EvServiceRequestSent<TSourceObject, TOrthogonal>();
306 this->postEvent(ev);
307 RCLCPP_DEBUG(getLogger(), "[%s] SERVICE REQUEST SENT EVENT", this->getName().c_str());
308 };
309
310 postFailureEvent = [this]()
311 {
312 auto * ev = new EvServiceFailure<TSourceObject, TOrthogonal>();
313 this->postEvent(ev);
314 RCLCPP_DEBUG(getLogger(), "[%s] SERVICE FAILURE EVENT", this->getName().c_str());
315 };
316 }
virtual std::string getName() const
rclcpp::Logger getLogger() const
std::function< void(const SharedResponse &)> postResponseEvent

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.

Here is the call graph for this function:

◆ onFailure()

template<typename ServiceType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpServiceClient< ServiceType >::onFailure ( void(T::* callback )(),
T * object )
inline

Helper method to connect a callback to the failure signal.

Template Parameters
TType of the callback object
Parameters
callbackMember function pointer to call on failure
objectObject instance that owns the callback
Returns
Signal connection handle

Definition at line 358 of file cp_service_client.hpp.

359 {
360 return this->getStateMachine()->createSignalConnection(onServiceFailure_, callback, object);
361 }
ISmaccStateMachine * getStateMachine()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onInitialize()

template<typename ServiceType >
void smacc2::client_core_components::CpServiceClient< ServiceType >::onInitialize ( )
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.

264 {
265 if (!serviceName)
266 {
267 RCLCPP_ERROR_STREAM(getLogger(), "[" << this->getName() << "] Service name not set!");
268 return;
269 }
270
271 RCLCPP_INFO_STREAM(
272 getLogger(), "[" << this->getName() << "] Initializing service client for: " << *serviceName);
273
274 client_ = getNode()->create_client<ServiceType>(*serviceName);
275
276 RCLCPP_INFO_STREAM(
277 getLogger(),
278 "[" << this->getName() << "] DONE Initializing service client for: " << *serviceName);
279 }
rclcpp::Node::SharedPtr getNode()

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.

Here is the call graph for this function:

◆ onRequestSent()

template<typename ServiceType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpServiceClient< ServiceType >::onRequestSent ( void(T::* callback )(),
T * object )
inline

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

Template Parameters
TType of the callback object
Parameters
callbackMember function pointer to call when request is sent
objectObject instance that owns the callback
Returns
Signal connection handle

Definition at line 344 of file cp_service_client.hpp.

345 {
346 return this->getStateMachine()->createSignalConnection(onServiceRequestSent_, callback, object);
347 }

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ onResponse()

template<typename ServiceType >
template<typename T >
boost::signals2::connection smacc2::client_core_components::CpServiceClient< ServiceType >::onResponse ( void(T::* callback )(const SharedResponse &),
T * object )
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.

Template Parameters
TType of the callback object
Parameters
callbackMember function pointer to call on response
objectObject instance that owns the callback
Returns
Signal connection handle

Definition at line 330 of file cp_service_client.hpp.

331 {
332 return this->getStateMachine()->createSignalConnection(onServiceResponse_, callback, object);
333 }
smacc2::SmaccSignal< void(const SharedResponse &)> onServiceResponse_

References smacc2::ISmaccStateMachine::createSignalConnection(), and smacc2::ISmaccComponent::getStateMachine().

Here is the call graph for this function:

◆ sendRequest()

template<typename ServiceType >
SharedFuture smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequest ( SharedRequest request)
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.

Parameters
requestShared pointer to the service request
Returns
SharedFuture Future for the service response

Definition at line 128 of file cp_service_client.hpp.

129 {
130 std::lock_guard<std::mutex> lock(serviceMutex_);
131
132 if (!client_)
133 {
134 RCLCPP_ERROR_STREAM(
135 getLogger(), "[" << this->getName() << "] Service client not initialized!");
136 throw std::runtime_error("Service client not initialized");
137 }
138
139 if (!client_->service_is_ready())
140 {
141 RCLCPP_WARN_STREAM(
142 getLogger(), "[" << this->getName() << "] Service not ready: " << *serviceName);
143 }
144
145 RCLCPP_INFO_STREAM(
146 getLogger(), "[" << this->getName() << "] Sending service request to: " << *serviceName);
147
148 // Send the async request
149 auto future = client_->async_send_request(request);
150 lastRequest_ = future;
151
152 // Emit signal that request was sent
155
156 return future;
157 }

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ sendRequestSync()

template<typename ServiceType >
SharedResponse smacc2::client_core_components::CpServiceClient< ServiceType >::sendRequestSync ( SharedRequest request)
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.

Parameters
requestShared pointer to the service request
Returns
SharedResponse Response from the service
Exceptions
std::runtime_errorif service call fails or times out

Definition at line 170 of file cp_service_client.hpp.

171 {
172 auto future = sendRequest(request);
173
174 // Wait for response with timeout
175 std::future_status status;
176 if (serviceTimeout)
177 {
178 status = future.wait_for(*serviceTimeout);
179 if (status == std::future_status::timeout)
180 {
181 RCLCPP_ERROR_STREAM(
182 getLogger(), "[" << this->getName() << "] Service call timed out: " << *serviceName);
185 throw std::runtime_error("Service call timeout");
186 }
187 }
188 else
189 {
190 future.wait();
191 }
192
193 // Get the response
194 try
195 {
196 auto response = future.get();
197
198 RCLCPP_INFO_STREAM(
199 getLogger(),
200 "[" << this->getName() << "] Service response received from: " << *serviceName);
201
202 // Emit signals and events
203 onServiceResponse_(response);
205
206 return response;
207 }
208 catch (const std::exception & e)
209 {
210 RCLCPP_ERROR_STREAM(
211 getLogger(),
212 "[" << this->getName() << "] Service call failed: " << *serviceName << " - " << e.what());
215 throw;
216 }
217 }
SharedFuture sendRequest(SharedRequest request)
Send a service request asynchronously.

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.

Here is the call graph for this function:

◆ waitForService()

template<typename ServiceType >
void smacc2::client_core_components::CpServiceClient< ServiceType >::waitForService ( )
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.

232 {
233 if (client_)
234 {
235 RCLCPP_INFO_STREAM(
236 getLogger(), "[" << this->getName() << "] Waiting for service: " << *serviceName);
237
238 if (serviceTimeout)
239 {
240 auto timeout = std::chrono::duration_cast<std::chrono::nanoseconds>(*serviceTimeout);
241 if (!client_->wait_for_service(timeout))
242 {
243 RCLCPP_WARN_STREAM(
244 getLogger(), "[" << this->getName() << "] Service wait timed out: " << *serviceName);
245 }
246 }
247 else
248 {
249 client_->wait_for_service();
250 }
251
252 RCLCPP_INFO_STREAM(
253 getLogger(), "[" << this->getName() << "] Service ready: " << *serviceName);
254 }
255 }

References smacc2::client_core_components::CpServiceClient< ServiceType >::client_, smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getName(), and smacc2::client_core_components::CpServiceClient< ServiceType >::serviceTimeout.

Here is the call graph for this function:

Member Data Documentation

◆ client_

◆ lastRequest_

template<typename ServiceType >
std::optional<SharedFuture> smacc2::client_core_components::CpServiceClient< ServiceType >::lastRequest_
private

◆ onServiceFailure_

template<typename ServiceType >
smacc2::SmaccSignal<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceFailure_

◆ onServiceRequestSent_

template<typename ServiceType >
smacc2::SmaccSignal<void()> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceRequestSent_

◆ onServiceResponse_

template<typename ServiceType >
smacc2::SmaccSignal<void(const SharedResponse &)> smacc2::client_core_components::CpServiceClient< ServiceType >::onServiceResponse_

◆ postFailureEvent

◆ postRequestSentEvent

◆ postResponseEvent

◆ serviceMutex_

template<typename ServiceType >
std::mutex smacc2::client_core_components::CpServiceClient< ServiceType >::serviceMutex_
private

◆ serviceName

template<typename ServiceType >
std::optional<std::string> smacc2::client_core_components::CpServiceClient< ServiceType >::serviceName

◆ serviceTimeout

template<typename ServiceType >
std::optional<std::chrono::milliseconds> smacc2::client_core_components::CpServiceClient< ServiceType >::serviceTimeout

The documentation for this class was generated from the following file: