Services¶
Client¶
-
class
rclpy.client.
Client
(context, client_handle, srv_type, srv_name, qos_profile, callback_group)¶ Create a container for a ROS service client.
Warning
Users should not create a service client with this constuctor, instead they should call
Node.create_client()
.- Parameters
context (
Context
) – The context associated with the service client.client_handle –
Handle
wrapping the underlyingrcl_client_t
object.srv_type (~SrvType) – The service type.
srv_name (
str
) – The name of the service.qos_profile (
QoSProfile
) – The quality of service profile to apply the service client.callback_group (
CallbackGroup
) – The callback group for the service client. IfNone
, then the nodes default callback group is used.
-
call
(request)¶ Make a service request and wait for the result.
Warning
Do not call this method in a callback or a deadlock may occur.
- Parameters
request (~SrvTypeRequest) – The service request.
- Return type
~SrvTypeResponse
- Returns
The service response.
- Raises
TypeError if the type of the passed request isn’t an instance of the Request type of the provided service when the client was constructed.
-
call_async
(request)¶ Make a service request and asyncronously get the result.
- Parameters
request (~SrvTypeRequest) – The service request.
- Return type
Future
- Returns
A future that completes when the request does.
- Raises
TypeError if the type of the passed request isn’t an instance of the Request type of the provided service when the client was constructed.
-
destroy
()¶
-
property
handle
¶
-
remove_pending_request
(future)¶ Remove a future from the list of pending requests.
This prevents a future from receiving a response and executing its done callbacks.
- Parameters
future (
Future
) – A future returned fromcall_async()
- Return type
None
-
service_is_ready
()¶ Check if there is a service server ready.
- Return type
bool
- Returns
True
if a server is ready,False
otherwise.
-
wait_for_service
(timeout_sec=None)¶ Wait for a service server to become ready.
Returns as soon as a server becomes ready or if the timeout expires.
- Parameters
timeout_sec (
Optional
[float
]) – Seconds to wait. IfNone
, then wait forever.- Return type
bool
- Returns
True
if server became ready while waiting orFalse
on a timeout.
Service¶
-
class
rclpy.service.
Service
(service_handle, srv_type, srv_name, callback, callback_group, qos_profile)¶ Create a container for a ROS service server.
Warning
Users should not create a service server with this constuctor, instead they should call
Node.create_service()
.- Parameters
context – The context associated with the service server.
service_handle – Capsule pointing to the underlying
rcl_service_t
object.srv_type (~SrvType) – The service type.
srv_name (
str
) – The name of the service.callback_group (
CallbackGroup
) – The callback group for the service server. IfNone
, then the nodes default callback group is used.qos_profile (
QoSProfile
) – The quality of service profile to apply the service server.
-
destroy
()¶
-
property
handle
¶
-
send_response
(response, header)¶ Send a service response.
- Parameters
response (~SrvTypeResponse) – The service response.
header – Capsule pointing to the service header from the original request.
- Raises
TypeError if the type of the passed response isn’t an instance of the Response type of the provided service when the service was constructed.
- Return type
None