Skip to content

Commit 2c32e20

Browse files
committed
Migrate to ServiceOptions
Signed-off-by: Michael X. Grey <[email protected]>
1 parent f12f874 commit 2c32e20

File tree

3 files changed

+89
-22
lines changed

3 files changed

+89
-22
lines changed

rclrs/src/node.rs

Lines changed: 47 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ pub use self::{builder::*, graph::*, primitive_options::*};
1616
use crate::{
1717
rcl_bindings::*, Client, ClientBase, Clock, Context, ContextHandle, GuardCondition,
1818
ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher, PublisherOptions,
19-
RclrsError, Service, ServiceBase, Subscription, SubscriptionBase, SubscriptionCallback,
19+
RclrsError, Service, ServiceBase, ServiceOptions, Subscription, SubscriptionBase, SubscriptionCallback,
2020
SubscriptionOptions, TimeSource, ENTITY_LIFECYCLE_MUTEX,
2121
};
2222

@@ -297,11 +297,49 @@ impl Node {
297297

298298
/// Creates a [`Service`][1].
299299
///
300+
/// Pass in only the service name for the `options` argument to use all default service options:
301+
/// ```
302+
/// # use rclrs::*;
303+
/// # let context = Context::new([]).unwrap();
304+
/// # let node = create_node(&context, "my_node").unwrap();
305+
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
306+
/// "my_service",
307+
/// |_info, _request| {
308+
/// println!("Received request!");
309+
/// test_msgs::srv::Empty_Response::default()
310+
/// },
311+
/// );
312+
/// ```
313+
///
314+
/// Take advantage of the [`IntoPrimitiveOptions`] API to easily build up the
315+
/// service options:
316+
///
317+
/// ```
318+
/// # use rclrs::*;
319+
/// # let context = Context::new([]).unwrap();
320+
/// # let node = create_node(&context, "my_node").unwrap();
321+
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
322+
/// "my_service"
323+
/// .keep_all()
324+
/// .transient_local(),
325+
/// |_info, _request| {
326+
/// println!("Received request!");
327+
/// test_msgs::srv::Empty_Response::default()
328+
/// },
329+
/// );
330+
/// ```
331+
///
332+
/// Any quality of service options that you explicitly specify will override
333+
/// the default service options. Any that you do not explicitly specify will
334+
/// remain the default service options. Note that services are generally
335+
/// expected to use [reliable][2], so is best not to change the reliability
336+
/// setting unless you know what you are doing.
337+
///
300338
/// [1]: crate::Service
301-
// TODO: make service's lifetime depend on node's lifetime
302-
pub fn create_service<T, F>(
339+
/// [2]: crate::QoSReliabilityPolicy::Reliable
340+
pub fn create_service<'a, T, F>(
303341
&self,
304-
topic: &str,
342+
options: impl Into<ServiceOptions<'a>>,
305343
callback: F,
306344
) -> Result<Arc<Service<T>>, RclrsError>
307345
where
@@ -310,7 +348,7 @@ impl Node {
310348
{
311349
let service = Arc::new(Service::<T>::new(
312350
Arc::clone(&self.handle),
313-
topic,
351+
options,
314352
callback,
315353
)?);
316354
{ self.services_mtx.lock().unwrap() }
@@ -327,22 +365,22 @@ impl Node {
327365
/// # let context = Context::new([]).unwrap();
328366
/// # let node = create_node(&context, "my_node").unwrap();
329367
/// let subscription = node.create_subscription(
330-
/// "my_subscription",
368+
/// "my_topic",
331369
/// |_msg: test_msgs::msg::Empty| {
332370
/// println!("Received message!");
333371
/// },
334372
/// );
335373
/// ```
336374
///
337-
/// Take advantage of [`IntoPrimitiveOptions`] to easily build up the
375+
/// Take advantage of the [`IntoPrimitiveOptions`] API to easily build up the
338376
/// subscription options:
339377
///
340378
/// ```
341379
/// # use rclrs::*;
342380
/// # let context = Context::new([]).unwrap();
343381
/// # let node = create_node(&context, "my_node").unwrap();
344382
/// let subscription = node.create_subscription(
345-
/// "my_subscription"
383+
/// "my_topic"
346384
/// .keep_last(100)
347385
/// .transient_local(),
348386
/// |_msg: test_msgs::msg::Empty| {
@@ -351,7 +389,7 @@ impl Node {
351389
/// );
352390
///
353391
/// let reliable_subscription = node.create_subscription(
354-
/// "my_reliable_subscription"
392+
/// "my_reliable_topic"
355393
/// .reliable(),
356394
/// |_msg: test_msgs::msg::Empty| {
357395
/// println!("Received message!");

rclrs/src/parameter/service.rs

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,8 @@ use rosidl_runtime_rs::Sequence;
99
use super::ParameterMap;
1010
use crate::{
1111
parameter::{DeclaredValue, ParameterKind, ParameterStorage},
12-
rmw_request_id_t, Node, RclrsError, Service,
12+
rmw_request_id_t, Node, RclrsError, Service, IntoPrimitiveOptions,
13+
QoSProfile,
1314
};
1415

1516
// The variables only exist to keep a strong reference to the services and are technically unused.
@@ -247,46 +248,52 @@ impl ParameterService {
247248
// destruction is made for the parameter map.
248249
let map = parameter_map.clone();
249250
let describe_parameters_service = node.create_service(
250-
&(fqn.clone() + "/describe_parameters"),
251+
(fqn.clone() + "/describe_parameters")
252+
.qos(QoSProfile::parameter_services_default()),
251253
move |_req_id: &rmw_request_id_t, req: DescribeParameters_Request| {
252254
let map = map.lock().unwrap();
253255
describe_parameters(req, &map)
254256
},
255257
)?;
256258
let map = parameter_map.clone();
257259
let get_parameter_types_service = node.create_service(
258-
&(fqn.clone() + "/get_parameter_types"),
260+
(fqn.clone() + "/get_parameter_types")
261+
.qos(QoSProfile::parameter_services_default()),
259262
move |_req_id: &rmw_request_id_t, req: GetParameterTypes_Request| {
260263
let map = map.lock().unwrap();
261264
get_parameter_types(req, &map)
262265
},
263266
)?;
264267
let map = parameter_map.clone();
265268
let get_parameters_service = node.create_service(
266-
&(fqn.clone() + "/get_parameters"),
269+
(fqn.clone() + "/get_parameters")
270+
.qos(QoSProfile::parameter_services_default()),
267271
move |_req_id: &rmw_request_id_t, req: GetParameters_Request| {
268272
let map = map.lock().unwrap();
269273
get_parameters(req, &map)
270274
},
271275
)?;
272276
let map = parameter_map.clone();
273277
let list_parameters_service = node.create_service(
274-
&(fqn.clone() + "/list_parameters"),
278+
(fqn.clone() + "/list_parameters")
279+
.qos(QoSProfile::parameter_services_default()),
275280
move |_req_id: &rmw_request_id_t, req: ListParameters_Request| {
276281
let map = map.lock().unwrap();
277282
list_parameters(req, &map)
278283
},
279284
)?;
280285
let map = parameter_map.clone();
281286
let set_parameters_service = node.create_service(
282-
&(fqn.clone() + "/set_parameters"),
287+
(fqn.clone() + "/set_parameters")
288+
.qos(QoSProfile::parameter_services_default()),
283289
move |_req_id: &rmw_request_id_t, req: SetParameters_Request| {
284290
let mut map = map.lock().unwrap();
285291
set_parameters(req, &mut map)
286292
},
287293
)?;
288294
let set_parameters_atomically_service = node.create_service(
289-
&(fqn.clone() + "/set_parameters_atomically"),
295+
(fqn.clone() + "/set_parameters_atomically")
296+
.qos(QoSProfile::parameter_services_default()),
290297
move |_req_id: &rmw_request_id_t, req: SetParametersAtomically_Request| {
291298
let mut map = parameter_map.lock().unwrap();
292299
set_parameters_atomically(req, &mut map)

rclrs/src/service.rs

Lines changed: 28 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ use rosidl_runtime_rs::Message;
99
use crate::{
1010
error::{RclReturnCode, ToResult},
1111
rcl_bindings::*,
12-
MessageCow, NodeHandle, RclrsError, ENTITY_LIFECYCLE_MUTEX,
12+
IntoPrimitiveOptions, MessageCow, NodeHandle, RclrsError, ENTITY_LIFECYCLE_MUTEX, QoSProfile,
1313
};
1414

1515
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -80,9 +80,9 @@ where
8080
T: rosidl_runtime_rs::Service,
8181
{
8282
/// Creates a new service.
83-
pub(crate) fn new<F>(
83+
pub(crate) fn new<'a, F>(
8484
node_handle: Arc<NodeHandle>,
85-
topic: &str,
85+
options: impl Into<ServiceOptions<'a>>,
8686
callback: F,
8787
) -> Result<Self, RclrsError>
8888
// This uses pub(crate) visibility to avoid instantiating this struct outside
@@ -91,17 +91,19 @@ where
9191
T: rosidl_runtime_rs::Service,
9292
F: Fn(&rmw_request_id_t, T::Request) -> T::Response + 'static + Send,
9393
{
94+
let ServiceOptions { name, qos } = options.into();
9495
// SAFETY: Getting a zero-initialized value is always safe.
9596
let mut rcl_service = unsafe { rcl_get_zero_initialized_service() };
9697
let type_support = <T as rosidl_runtime_rs::Service>::get_type_support()
9798
as *const rosidl_service_type_support_t;
98-
let topic_c_string = CString::new(topic).map_err(|err| RclrsError::StringContainsNul {
99+
let topic_c_string = CString::new(name).map_err(|err| RclrsError::StringContainsNul {
99100
err,
100-
s: topic.into(),
101+
s: name.into(),
101102
})?;
102103

103104
// SAFETY: No preconditions for this function.
104-
let service_options = unsafe { rcl_service_get_default_options() };
105+
let mut service_options = unsafe { rcl_service_get_default_options() };
106+
service_options.qos = qos.into();
105107

106108
{
107109
let rcl_node = node_handle.rcl_node.lock().unwrap();
@@ -181,6 +183,26 @@ where
181183
}
182184
}
183185

186+
/// `ServiceOptions are used by [`Node::create_service`][1] to initialize a
187+
/// [`Service`] provider.
188+
#[derive(Debug, Clone)]
189+
#[non_exhaustive]
190+
pub struct ServiceOptions<'a> {
191+
/// The name for the service
192+
pub name: &'a str,
193+
/// The quality of service for the service.
194+
pub qos: QoSProfile,
195+
}
196+
197+
impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for ServiceOptions<'a> {
198+
fn from(value: T) -> Self {
199+
let options = value.into_primitive_options();
200+
let mut qos = QoSProfile::services_default();
201+
options.apply(&mut qos);
202+
Self { name: options.name, qos }
203+
}
204+
}
205+
184206
impl<T> ServiceBase for Service<T>
185207
where
186208
T: rosidl_runtime_rs::Service,

0 commit comments

Comments
 (0)