Skip to content

Commit 6c61c9c

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

File tree

5 files changed

+100
-36
lines changed

5 files changed

+100
-36
lines changed

rclrs/src/client.rs

Lines changed: 38 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ use rosidl_runtime_rs::Message;
1111
use crate::{
1212
error::{RclReturnCode, ToResult},
1313
rcl_bindings::*,
14-
MessageCow, NodeHandle, RclrsError, ENTITY_LIFECYCLE_MUTEX,
14+
IntoPrimitiveOptions, MessageCow, NodeHandle, QoSProfile, RclrsError, ENTITY_LIFECYCLE_MUTEX,
1515
};
1616

1717
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -83,23 +83,29 @@ where
8383
T: rosidl_runtime_rs::Service,
8484
{
8585
/// Creates a new client.
86-
pub(crate) fn new(node_handle: Arc<NodeHandle>, topic: &str) -> Result<Self, RclrsError>
86+
pub(crate) fn new<'a>(
87+
node_handle: Arc<NodeHandle>,
88+
options: impl Into<ClientOptions<'a>>,
89+
) -> Result<Self, RclrsError>
8790
// This uses pub(crate) visibility to avoid instantiating this struct outside
8891
// [`Node::create_client`], see the struct's documentation for the rationale
8992
where
9093
T: rosidl_runtime_rs::Service,
9194
{
95+
let ClientOptions { service_name, qos } = options.into();
9296
// SAFETY: Getting a zero-initialized value is always safe.
9397
let mut rcl_client = unsafe { rcl_get_zero_initialized_client() };
9498
let type_support = <T as rosidl_runtime_rs::Service>::get_type_support()
9599
as *const rosidl_service_type_support_t;
96-
let topic_c_string = CString::new(topic).map_err(|err| RclrsError::StringContainsNul {
97-
err,
98-
s: topic.into(),
99-
})?;
100+
let topic_c_string =
101+
CString::new(service_name).map_err(|err| RclrsError::StringContainsNul {
102+
err,
103+
s: service_name.into(),
104+
})?;
100105

101106
// SAFETY: No preconditions for this function.
102-
let client_options = unsafe { rcl_client_get_default_options() };
107+
let mut client_options = unsafe { rcl_client_get_default_options() };
108+
client_options.qos = qos.into();
103109

104110
{
105111
let rcl_node = node_handle.rcl_node.lock().unwrap();
@@ -275,6 +281,31 @@ where
275281
}
276282
}
277283

284+
/// `ClientOptions` are used by [`Node::create_client`][1] to initialize a
285+
/// [`Client`] for a service.
286+
///
287+
/// [1]: crate::NodeState::create_client
288+
#[derive(Debug, Clone)]
289+
#[non_exhaustive]
290+
pub struct ClientOptions<'a> {
291+
/// The name of the service that this client will send requests to
292+
pub service_name: &'a str,
293+
/// The quality of the service profile for this client
294+
pub qos: QoSProfile,
295+
}
296+
297+
impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for ClientOptions<'a> {
298+
fn from(value: T) -> Self {
299+
let options = value.into_primitive_options();
300+
let mut qos = QoSProfile::services_default();
301+
options.apply(&mut qos);
302+
Self {
303+
service_name: options.name,
304+
qos,
305+
}
306+
}
307+
}
308+
278309
impl<T> ClientBase for Client<T>
279310
where
280311
T: rosidl_runtime_rs::Service,

rclrs/src/node.rs

Lines changed: 42 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -14,10 +14,11 @@ use rosidl_runtime_rs::Message;
1414

1515
pub use self::{builder::*, graph::*, primitive_options::*};
1616
use crate::{
17-
rcl_bindings::*, Client, ClientBase, Clock, Context, ContextHandle, GuardCondition,
18-
ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher, PublisherOptions,
19-
RclrsError, Service, ServiceBase, ServiceOptions, Subscription, SubscriptionBase, SubscriptionCallback,
20-
SubscriptionOptions, TimeSource, ENTITY_LIFECYCLE_MUTEX,
17+
rcl_bindings::*, Client, ClientBase, ClientOptions, Clock, Context, ContextHandle,
18+
GuardCondition, ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher,
19+
PublisherOptions, RclrsError, Service, ServiceBase, ServiceOptions, Subscription,
20+
SubscriptionBase, SubscriptionCallback, SubscriptionOptions, TimeSource,
21+
ENTITY_LIFECYCLE_MUTEX,
2122
};
2223

2324
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -200,13 +201,45 @@ impl Node {
200201

201202
/// Creates a [`Client`][1].
202203
///
203-
/// [1]: crate::Client
204-
// TODO: make client's lifetime depend on node's lifetime
205-
pub fn create_client<T>(&self, topic: &str) -> Result<Arc<Client<T>>, RclrsError>
204+
/// Pass in only the service name for the `options` argument to use all default client options:
205+
/// ```
206+
/// # use rclrs::*;
207+
/// # let context = Context::new([]).unwrap();
208+
/// # let node = create_node(&context, "my_node").unwrap();
209+
/// let client = node.create_client::<test_msgs::srv::Empty>(
210+
/// "my_service"
211+
/// )
212+
/// .unwrap();
213+
/// ```
214+
///
215+
/// Take advantage of the [`IntoPrimitiveOptions`] API to easily build up the
216+
/// client options:
217+
///
218+
/// ```
219+
/// # use rclrs::*;
220+
/// # let context = Context::new([]).unwrap();
221+
/// # let node = create_node(&context, "my_node").unwrap();
222+
/// let client = node.create_client::<test_msgs::srv::Empty>(
223+
/// "my_service"
224+
/// .keep_all()
225+
/// .transient_local()
226+
/// )
227+
/// .unwrap();
228+
/// ```
229+
///
230+
/// Any quality of service options that you explicitly specify will override
231+
/// the default service options. Any that you do not explicitly specify will
232+
/// remain the default service options. Note that clients are generally
233+
/// expected to use [reliable][2], so it's best not to change the reliability
234+
/// setting unless you know what you are doing.
235+
pub fn create_client<'a, T>(
236+
&self,
237+
options: impl Into<ClientOptions<'a>>,
238+
) -> Result<Arc<Client<T>>, RclrsError>
206239
where
207240
T: rosidl_runtime_rs::Service,
208241
{
209-
let client = Arc::new(Client::<T>::new(Arc::clone(&self.handle), topic)?);
242+
let client = Arc::new(Client::<T>::new(Arc::clone(&self.handle), options)?);
210243
{ self.clients_mtx.lock().unwrap() }.push(Arc::downgrade(&client) as Weak<dyn ClientBase>);
211244
Ok(client)
212245
}
@@ -332,7 +365,7 @@ impl Node {
332365
/// Any quality of service options that you explicitly specify will override
333366
/// the default service options. Any that you do not explicitly specify will
334367
/// remain the default service options. Note that services are generally
335-
/// expected to use [reliable][2], so is best not to change the reliability
368+
/// expected to use [reliable][2], so it's best not to change the reliability
336369
/// setting unless you know what you are doing.
337370
///
338371
/// [1]: crate::Service

rclrs/src/parameter/service.rs

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,7 @@ 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, IntoPrimitiveOptions,
13-
QoSProfile,
12+
rmw_request_id_t, IntoPrimitiveOptions, Node, QoSProfile, RclrsError, Service,
1413
};
1514

1615
// The variables only exist to keep a strong reference to the services and are technically unused.
@@ -248,52 +247,47 @@ impl ParameterService {
248247
// destruction is made for the parameter map.
249248
let map = parameter_map.clone();
250249
let describe_parameters_service = node.create_service(
251-
(fqn.clone() + "/describe_parameters")
252-
.qos(QoSProfile::parameter_services_default()),
250+
(fqn.clone() + "/describe_parameters").qos(QoSProfile::parameter_services_default()),
253251
move |_req_id: &rmw_request_id_t, req: DescribeParameters_Request| {
254252
let map = map.lock().unwrap();
255253
describe_parameters(req, &map)
256254
},
257255
)?;
258256
let map = parameter_map.clone();
259257
let get_parameter_types_service = node.create_service(
260-
(fqn.clone() + "/get_parameter_types")
261-
.qos(QoSProfile::parameter_services_default()),
258+
(fqn.clone() + "/get_parameter_types").qos(QoSProfile::parameter_services_default()),
262259
move |_req_id: &rmw_request_id_t, req: GetParameterTypes_Request| {
263260
let map = map.lock().unwrap();
264261
get_parameter_types(req, &map)
265262
},
266263
)?;
267264
let map = parameter_map.clone();
268265
let get_parameters_service = node.create_service(
269-
(fqn.clone() + "/get_parameters")
270-
.qos(QoSProfile::parameter_services_default()),
266+
(fqn.clone() + "/get_parameters").qos(QoSProfile::parameter_services_default()),
271267
move |_req_id: &rmw_request_id_t, req: GetParameters_Request| {
272268
let map = map.lock().unwrap();
273269
get_parameters(req, &map)
274270
},
275271
)?;
276272
let map = parameter_map.clone();
277273
let list_parameters_service = node.create_service(
278-
(fqn.clone() + "/list_parameters")
279-
.qos(QoSProfile::parameter_services_default()),
274+
(fqn.clone() + "/list_parameters").qos(QoSProfile::parameter_services_default()),
280275
move |_req_id: &rmw_request_id_t, req: ListParameters_Request| {
281276
let map = map.lock().unwrap();
282277
list_parameters(req, &map)
283278
},
284279
)?;
285280
let map = parameter_map.clone();
286281
let set_parameters_service = node.create_service(
287-
(fqn.clone() + "/set_parameters")
288-
.qos(QoSProfile::parameter_services_default()),
282+
(fqn.clone() + "/set_parameters").qos(QoSProfile::parameter_services_default()),
289283
move |_req_id: &rmw_request_id_t, req: SetParameters_Request| {
290284
let mut map = map.lock().unwrap();
291285
set_parameters(req, &mut map)
292286
},
293287
)?;
294288
let set_parameters_atomically_service = node.create_service(
295289
(fqn.clone() + "/set_parameters_atomically")
296-
.qos(QoSProfile::parameter_services_default()),
290+
.qos(QoSProfile::parameter_services_default()),
297291
move |_req_id: &rmw_request_id_t, req: SetParametersAtomically_Request| {
298292
let mut map = parameter_map.lock().unwrap();
299293
set_parameters_atomically(req, &mut map)

rclrs/src/publisher.rs

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ use crate::{
1111
error::{RclrsError, ToResult},
1212
qos::QoSProfile,
1313
rcl_bindings::*,
14-
NodeHandle, ENTITY_LIFECYCLE_MUTEX, IntoPrimitiveOptions,
14+
IntoPrimitiveOptions, NodeHandle, ENTITY_LIFECYCLE_MUTEX,
1515
};
1616

1717
mod loaned_message;
@@ -249,7 +249,10 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for PublisherOptions<'a> {
249249
let options = value.into_primitive_options();
250250
let mut qos = QoSProfile::topics_default();
251251
options.apply(&mut qos);
252-
Self { topic: options.name, qos }
252+
Self {
253+
topic: options.name,
254+
qos,
255+
}
253256
}
254257
}
255258

@@ -294,9 +297,9 @@ mod tests {
294297
.node1
295298
.create_publisher::<msg::Empty>("graph_test_topic_1")?;
296299
let topic1 = node_1_empty_publisher.topic_name();
297-
let node_1_basic_types_publisher = graph.node1.create_publisher::<msg::BasicTypes>(
298-
"graph_test_topic_2"
299-
)?;
300+
let node_1_basic_types_publisher = graph
301+
.node1
302+
.create_publisher::<msg::BasicTypes>("graph_test_topic_2")?;
300303
let topic2 = node_1_basic_types_publisher.topic_name();
301304
let node_2_default_publisher = graph
302305
.node2

rclrs/src/service.rs

Lines changed: 5 additions & 2 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-
IntoPrimitiveOptions, MessageCow, NodeHandle, RclrsError, ENTITY_LIFECYCLE_MUTEX, QoSProfile,
12+
IntoPrimitiveOptions, MessageCow, NodeHandle, QoSProfile, RclrsError, ENTITY_LIFECYCLE_MUTEX,
1313
};
1414

1515
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -199,7 +199,10 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for ServiceOptions<'a> {
199199
let options = value.into_primitive_options();
200200
let mut qos = QoSProfile::services_default();
201201
options.apply(&mut qos);
202-
Self { name: options.name, qos }
202+
Self {
203+
name: options.name,
204+
qos,
205+
}
203206
}
204207
}
205208

0 commit comments

Comments
 (0)