Skip to content

Commit 2dff995

Browse files
committed
Migrate create_service to use impl Into<ServiceOptions>
Signed-off-by: Michael X. Grey <[email protected]>
1 parent 5b69188 commit 2dff995

File tree

3 files changed

+89
-21
lines changed

3 files changed

+89
-21
lines changed

rclrs/src/node.rs

Lines changed: 47 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ use rosidl_runtime_rs::Message;
2121
use crate::{
2222
rcl_bindings::*, Client, ClientBase, Clock, ContextHandle, GuardCondition,
2323
ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher, PublisherOptions,
24-
RclrsError, Service, ServiceBase, Subscription, SubscriptionBase, SubscriptionCallback,
24+
RclrsError, Service, ServiceBase, ServiceOptions, Subscription, SubscriptionBase, SubscriptionCallback,
2525
SubscriptionOptions, TimeSource, ENTITY_LIFECYCLE_MUTEX,
2626
};
2727

@@ -284,11 +284,50 @@ impl NodeState {
284284

285285
/// Creates a [`Service`][1].
286286
///
287+
/// Pass in only the service name for the `options` argument to use all default service options:
288+
/// ```
289+
/// # use rclrs::*;
290+
/// # let executor = Context::default().create_basic_executor();
291+
/// # let node = executor.create_node("my_node").unwrap();
292+
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
293+
/// "my_service",
294+
/// |_info, _request| {
295+
/// println!("Received request!");
296+
/// test_msgs::srv::Empty_Response::default()
297+
/// },
298+
/// );
299+
/// ```
300+
///
301+
/// Take advantage of the [`IntoPrimitiveOptions`] API to easily build up the
302+
/// service options:
303+
///
304+
/// ```
305+
/// # use rclrs::*;
306+
/// # let executor = Context::default().create_basic_executor();
307+
/// # let node = executor.create_node("my_node").unwrap();
308+
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
309+
/// "my_service"
310+
/// .keep_all()
311+
/// .transient_local(),
312+
/// |_info, _request| {
313+
/// println!("Received request!");
314+
/// test_msgs::srv::Empty_Response::default()
315+
/// },
316+
/// );
317+
/// ```
318+
///
319+
/// Any quality of service options that you explicitly specify will override
320+
/// the default service options. Any that you do not explicitly specify will
321+
/// remain the default service options. Note that services are generally
322+
/// expected to use [reliable][2], so is best not to change the reliability
323+
/// setting unless you know what you are doing.
324+
///
287325
/// [1]: crate::Service
326+
/// [2]: crate::QoSReliabilityPolicy::Reliable
288327
// TODO: make service's lifetime depend on node's lifetime
289-
pub fn create_service<T, F>(
328+
pub fn create_service<'a, T, F>(
290329
&self,
291-
topic: &str,
330+
options: impl Into<ServiceOptions<'a>>,
292331
callback: F,
293332
) -> Result<Arc<Service<T>>, RclrsError>
294333
where
@@ -297,7 +336,7 @@ impl NodeState {
297336
{
298337
let service = Arc::new(Service::<T>::new(
299338
Arc::clone(&self.handle),
300-
topic,
339+
options,
301340
callback,
302341
)?);
303342
{ self.services_mtx.lock().unwrap() }
@@ -313,22 +352,22 @@ impl NodeState {
313352
/// # let executor = Context::default().create_basic_executor();
314353
/// # let node = executor.create_node("my_node").unwrap();
315354
/// let subscription = node.create_subscription(
316-
/// "my_subscription",
355+
/// "my_topic",
317356
/// |_msg: test_msgs::msg::Empty| {
318357
/// println!("Received message!");
319358
/// },
320359
/// );
321360
/// ```
322361
///
323-
/// Take advantage of [`IntoPrimitiveOptions`] to easily build up the
362+
/// Take advantage of the [`IntoPrimitiveOptions`] API to easily build up the
324363
/// subscription options:
325364
///
326365
/// ```
327366
/// # use rclrs::*;
328367
/// # let executor = Context::default().create_basic_executor();
329368
/// # let node = executor.create_node("my_node").unwrap();
330369
/// let subscription = node.create_subscription(
331-
/// "my_subscription"
370+
/// "my_topic"
332371
/// .keep_last(100)
333372
/// .transient_local(),
334373
/// |_msg: test_msgs::msg::Empty| {
@@ -337,7 +376,7 @@ impl NodeState {
337376
/// );
338377
///
339378
/// let reliable_subscription = node.create_subscription(
340-
/// "my_reliable_subscription"
379+
/// "my_reliable_topic"
341380
/// .reliable(),
342381
/// |_msg: test_msgs::msg::Empty| {
343382
/// 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)