Skip to content

Commit 433a348

Browse files
committed
Migrate to SubscriptionOptions
Signed-off-by: Michael X. Grey <[email protected]>
1 parent 066dd7c commit 433a348

File tree

10 files changed

+384
-60
lines changed

10 files changed

+384
-60
lines changed

examples/message_demo/src/message_demo.rs

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -153,13 +153,11 @@ fn demonstrate_pubsub() -> Result<(), Error> {
153153
let _idiomatic_subscription = node
154154
.create_subscription::<rclrs_example_msgs::msg::VariousTypes, _>(
155155
"topic",
156-
rclrs::QOS_PROFILE_DEFAULT,
157156
move |_msg: rclrs_example_msgs::msg::VariousTypes| println!("Got idiomatic message!"),
158157
)?;
159158
let _direct_subscription = node
160159
.create_subscription::<rclrs_example_msgs::msg::rmw::VariousTypes, _>(
161160
"topic",
162-
rclrs::QOS_PROFILE_DEFAULT,
163161
move |_msg: rclrs_example_msgs::msg::rmw::VariousTypes| {
164162
println!("Got RMW-native message!")
165163
},

examples/minimal_pub_sub/src/minimal_subscriber.rs

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ fn main() -> Result<(), Error> {
1111

1212
let _subscription = node.create_subscription::<std_msgs::msg::String, _>(
1313
"topic",
14-
rclrs::QOS_PROFILE_DEFAULT,
1514
move |msg: std_msgs::msg::String| {
1615
num_messages += 1;
1716
println!("I heard: '{}'", msg.data);

examples/minimal_pub_sub/src/minimal_two_nodes.rs

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,6 @@ impl MinimalSubscriber {
2929
.node
3030
.create_subscription::<std_msgs::msg::String, _>(
3131
topic,
32-
rclrs::QOS_PROFILE_DEFAULT,
3332
move |msg: std_msgs::msg::String| {
3433
minimal_subscriber_aux.callback(msg);
3534
},

examples/minimal_pub_sub/src/zero_copy_subscriber.rs

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ fn main() -> Result<(), Error> {
1111

1212
let _subscription = node.create_subscription::<std_msgs::msg::UInt32, _>(
1313
"topic",
14-
rclrs::QOS_PROFILE_DEFAULT,
1514
move |msg: rclrs::ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
1615
num_messages += 1;
1716
println!("I heard: '{}'", msg.data);

examples/rust_pubsub/src/simple_subscriber.rs

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
use rclrs::{create_node, Context, Node, RclrsError, Subscription, QOS_PROFILE_DEFAULT};
1+
use rclrs::{create_node, Context, Node, RclrsError, Subscription};
22
use std::{
33
env,
44
sync::{Arc, Mutex},
@@ -19,7 +19,6 @@ impl SimpleSubscriptionNode {
1919
let _subscriber = node
2020
.create_subscription::<StringMsg, _>(
2121
"publish_hello",
22-
QOS_PROFILE_DEFAULT,
2322
move |msg: StringMsg| {
2423
*data_mut.lock().unwrap() = Some(msg);
2524
},

rclrs/src/node.rs

Lines changed: 49 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
mod builder;
22
mod graph;
3+
mod primitive_options;
34
use std::{
45
cmp::PartialEq,
56
ffi::CStr,
@@ -11,12 +12,12 @@ use std::{
1112

1213
use rosidl_runtime_rs::Message;
1314

14-
pub use self::{builder::*, graph::*};
15+
pub use self::{builder::*, graph::*, primitive_options::*};
1516
use crate::{
1617
rcl_bindings::*, Client, ClientBase, Clock, Context, ContextHandle, GuardCondition,
1718
ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher, QoSProfile,
1819
RclrsError, Service, ServiceBase, Subscription, SubscriptionBase, SubscriptionCallback,
19-
TimeSource, ENTITY_LIFECYCLE_MUTEX,
20+
SubscriptionOptions, TimeSource, ENTITY_LIFECYCLE_MUTEX,
2021
};
2122

2223
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -292,21 +293,56 @@ impl Node {
292293

293294
/// Creates a [`Subscription`][1].
294295
///
295-
/// [1]: crate::Subscription
296-
// TODO: make subscription's lifetime depend on node's lifetime
297-
pub fn create_subscription<T, Args>(
296+
///
297+
/// Pass in only the topic name for the `options` argument to use all default subscription options:
298+
/// ```
299+
/// # use rclrs::*;
300+
/// # let context = Context::new([]).unwrap();
301+
/// # let node = create_node(&context, "my_node").unwrap();
302+
/// let subscription = node.create_subscription(
303+
/// "my_subscription",
304+
/// |_msg: test_msgs::msg::Empty| {
305+
/// println!("Received message!");
306+
/// },
307+
/// );
308+
/// ```
309+
///
310+
/// Take advantage of [`IntoPrimitiveOptions`] to easily build up the
311+
/// subscription options:
312+
///
313+
/// ```
314+
/// # use rclrs::*;
315+
/// # let context = Context::new([]).unwrap();
316+
/// # let node = create_node(&context, "my_node").unwrap();
317+
/// let subscription = node.create_subscription(
318+
/// "my_subscription"
319+
/// .keep_last(100)
320+
/// .transient_local(),
321+
/// |_msg: test_msgs::msg::Empty| {
322+
/// println!("Received message!");
323+
/// },
324+
/// );
325+
///
326+
/// let reliable_subscription = node.create_subscription(
327+
/// "my_reliable_subscription"
328+
/// .reliable(),
329+
/// |_msg: test_msgs::msg::Empty| {
330+
/// println!("Received message!");
331+
/// },
332+
/// );
333+
/// ```
334+
///
335+
pub fn create_subscription<'a, T, Args>(
298336
&self,
299-
topic: &str,
300-
qos: QoSProfile,
337+
options: impl Into<SubscriptionOptions<'a>>,
301338
callback: impl SubscriptionCallback<T, Args>,
302339
) -> Result<Arc<Subscription<T>>, RclrsError>
303340
where
304341
T: Message,
305342
{
306343
let subscription = Arc::new(Subscription::<T>::new(
307344
Arc::clone(&self.handle),
308-
topic,
309-
qos,
345+
options,
310346
callback,
311347
)?);
312348
{ self.subscriptions_mtx.lock() }
@@ -461,8 +497,7 @@ pub(crate) unsafe fn call_string_getter_with_rcl_node(
461497

462498
#[cfg(test)]
463499
mod tests {
464-
use super::*;
465-
use crate::test_helpers::*;
500+
use crate::{test_helpers::*, *};
466501

467502
#[test]
468503
fn traits() {
@@ -472,25 +507,20 @@ mod tests {
472507

473508
#[test]
474509
fn test_topic_names_and_types() -> Result<(), RclrsError> {
475-
use crate::QOS_PROFILE_SYSTEM_DEFAULT;
476510
use test_msgs::msg;
477511

478512
let graph = construct_test_graph("test_topics_graph")?;
479513

480514
let _node_1_defaults_subscription = graph.node1.create_subscription::<msg::Defaults, _>(
481515
"graph_test_topic_3",
482-
QOS_PROFILE_SYSTEM_DEFAULT,
483516
|_msg: msg::Defaults| {},
484517
)?;
485-
let _node_2_empty_subscription = graph.node2.create_subscription::<msg::Empty, _>(
486-
"graph_test_topic_1",
487-
QOS_PROFILE_SYSTEM_DEFAULT,
488-
|_msg: msg::Empty| {},
489-
)?;
518+
let _node_2_empty_subscription = graph
519+
.node2
520+
.create_subscription::<msg::Empty, _>("graph_test_topic_1", |_msg: msg::Empty| {})?;
490521
let _node_2_basic_types_subscription =
491522
graph.node2.create_subscription::<msg::BasicTypes, _>(
492523
"graph_test_topic_2",
493-
QOS_PROFILE_SYSTEM_DEFAULT,
494524
|_msg: msg::BasicTypes| {},
495525
)?;
496526

0 commit comments

Comments
 (0)