Skip to content

Commit becc938

Browse files
authored
Options pattern (spin-off of #427) (#429)
* Migrate to SubscriptionOptions Signed-off-by: Michael X. Grey <[email protected]> * Migrate to PublisherOptions Signed-off-by: Michael X. Grey <[email protected]> * Migrate to ServiceOptions Signed-off-by: Michael X. Grey <[email protected]> * Migrate to ClientOptions Signed-off-by: Michael X. Grey <[email protected]> * Enable direct creation of the _Options for all primitive types Signed-off-by: Michael X. Grey <[email protected]> * Fix example formatting Signed-off-by: Michael X. Grey <[email protected]> * Fix docs Signed-off-by: Michael X. Grey <[email protected]> * Make deadline, liveliness_lease, and lifespan all symmetric Signed-off-by: Michael X. Grey <[email protected]> * Add an API to the primitive options builder for avoiding ROS namespace conventions Signed-off-by: Michael X. Grey <[email protected]> * Retrigger CI Signed-off-by: Michael X. Grey <[email protected]> * Fix: Override all profile options when using .qos Signed-off-by: Michael X. Grey <[email protected]> * Reword the warning for system_qos Signed-off-by: Michael X. Grey <[email protected]> * Reword the warning for QoSProfile::system_default Signed-off-by: Michael X. Grey <[email protected]> * Rename PrimitiveOptions::apply to apply_to Signed-off-by: Michael X. Grey <[email protected]> --------- Signed-off-by: Michael X. Grey <[email protected]> Signed-off-by: Michael X. Grey <[email protected]>
1 parent 0fe1f21 commit becc938

17 files changed

+724
-145
lines changed

examples/message_demo/src/message_demo.rs

+4-8
Original file line numberDiff line numberDiff line change
@@ -143,23 +143,19 @@ fn demonstrate_pubsub() -> Result<(), Error> {
143143
let mut executor = Context::default_from_env()?.create_basic_executor();
144144
let node = executor.create_node("message_demo")?;
145145

146-
let idiomatic_publisher = node
147-
.create_publisher::<rclrs_example_msgs::msg::VariousTypes>("topic", QOS_PROFILE_DEFAULT)?;
148-
let direct_publisher = node.create_publisher::<rclrs_example_msgs::msg::rmw::VariousTypes>(
149-
"topic",
150-
QOS_PROFILE_DEFAULT,
151-
)?;
146+
let idiomatic_publisher =
147+
node.create_publisher::<rclrs_example_msgs::msg::VariousTypes>("topic")?;
148+
let direct_publisher =
149+
node.create_publisher::<rclrs_example_msgs::msg::rmw::VariousTypes>("topic")?;
152150

153151
let _idiomatic_subscription = node
154152
.create_subscription::<rclrs_example_msgs::msg::VariousTypes, _>(
155153
"topic",
156-
QOS_PROFILE_DEFAULT,
157154
move |_msg: rclrs_example_msgs::msg::VariousTypes| println!("Got idiomatic message!"),
158155
)?;
159156
let _direct_subscription = node
160157
.create_subscription::<rclrs_example_msgs::msg::rmw::VariousTypes, _>(
161158
"topic",
162-
QOS_PROFILE_DEFAULT,
163159
move |_msg: rclrs_example_msgs::msg::rmw::VariousTypes| {
164160
println!("Got RMW-native message!")
165161
},

examples/minimal_pub_sub/src/minimal_publisher.rs

+1-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ fn main() -> Result<(), Error> {
77

88
let node = executor.create_node("minimal_publisher")?;
99

10-
let publisher = node.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;
10+
let publisher = node.create_publisher::<std_msgs::msg::String>("topic")?;
1111

1212
let mut message = std_msgs::msg::String::default();
1313

examples/minimal_pub_sub/src/minimal_subscriber.rs

-1
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-
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

+1-3
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@ impl MinimalSubscriber {
2626
.node
2727
.create_subscription::<std_msgs::msg::String, _>(
2828
topic,
29-
QOS_PROFILE_DEFAULT,
3029
move |msg: std_msgs::msg::String| {
3130
minimal_subscriber_aux.callback(msg);
3231
},
@@ -55,8 +54,7 @@ fn main() -> Result<(), Error> {
5554
let _subscriber_node_two =
5655
MinimalSubscriber::new(&executor, "minimal_subscriber_two", "topic")?;
5756

58-
let publisher =
59-
publisher_node.create_publisher::<std_msgs::msg::String>("topic", QOS_PROFILE_DEFAULT)?;
57+
let publisher = publisher_node.create_publisher::<std_msgs::msg::String>("topic")?;
6058

6159
std::thread::spawn(move || -> Result<(), RclrsError> {
6260
let mut message = std_msgs::msg::String::default();

examples/minimal_pub_sub/src/zero_copy_publisher.rs

+1-2
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,7 @@ fn main() -> Result<(), Error> {
77

88
let node = executor.create_node("minimal_publisher")?;
99

10-
let publisher =
11-
node.create_publisher::<std_msgs::msg::rmw::UInt32>("topic", QOS_PROFILE_DEFAULT)?;
10+
let publisher = node.create_publisher::<std_msgs::msg::rmw::UInt32>("topic")?;
1211

1312
let mut publish_count: u32 = 1;
1413

examples/minimal_pub_sub/src/zero_copy_subscriber.rs

+1-2
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,7 @@ fn main() -> Result<(), Error> {
1010

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

examples/rust_pubsub/src/simple_publisher.rs

+1-3
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,7 @@ struct SimplePublisher {
99
impl SimplePublisher {
1010
fn new(executor: &Executor) -> Result<Self, RclrsError> {
1111
let node = executor.create_node("simple_publisher").unwrap();
12-
let publisher = node
13-
.create_publisher("publish_hello", QOS_PROFILE_DEFAULT)
14-
.unwrap();
12+
let publisher = node.create_publisher("publish_hello").unwrap();
1513
Ok(Self { publisher })
1614
}
1715

examples/rust_pubsub/src/simple_subscriber.rs

+3-7
Original file line numberDiff line numberDiff line change
@@ -17,13 +17,9 @@ impl SimpleSubscriptionNode {
1717
let data: Arc<Mutex<Option<StringMsg>>> = Arc::new(Mutex::new(None));
1818
let data_mut: Arc<Mutex<Option<StringMsg>>> = Arc::clone(&data);
1919
let _subscriber = node
20-
.create_subscription::<StringMsg, _>(
21-
"publish_hello",
22-
QOS_PROFILE_DEFAULT,
23-
move |msg: StringMsg| {
24-
*data_mut.lock().unwrap() = Some(msg);
25-
},
26-
)
20+
.create_subscription::<StringMsg, _>("publish_hello", move |msg: StringMsg| {
21+
*data_mut.lock().unwrap() = Some(msg);
22+
})
2723
.unwrap();
2824
Ok(Self { _subscriber, data })
2925
}

rclrs/src/client.rs

+46-7
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@ use rosidl_runtime_rs::Message;
1111
use crate::{
1212
error::{RclReturnCode, ToResult},
1313
rcl_bindings::*,
14-
MessageCow, Node, NodeHandle, RclrsError, ENTITY_LIFECYCLE_MUTEX,
14+
IntoPrimitiveOptions, MessageCow, Node, NodeHandle, QoSProfile, RclrsError,
15+
ENTITY_LIFECYCLE_MUTEX,
1516
};
1617

1718
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -87,23 +88,29 @@ where
8788
T: rosidl_runtime_rs::Service,
8889
{
8990
/// Creates a new client.
90-
pub(crate) fn new(node: &Arc<Node>, topic: &str) -> Result<Self, RclrsError>
91+
pub(crate) fn new<'a>(
92+
node: &Arc<Node>,
93+
options: impl Into<ClientOptions<'a>>,
94+
) -> Result<Self, RclrsError>
9195
// This uses pub(crate) visibility to avoid instantiating this struct outside
9296
// [`Node::create_client`], see the struct's documentation for the rationale
9397
where
9498
T: rosidl_runtime_rs::Service,
9599
{
100+
let ClientOptions { service_name, qos } = options.into();
96101
// SAFETY: Getting a zero-initialized value is always safe.
97102
let mut rcl_client = unsafe { rcl_get_zero_initialized_client() };
98103
let type_support = <T as rosidl_runtime_rs::Service>::get_type_support()
99104
as *const rosidl_service_type_support_t;
100-
let topic_c_string = CString::new(topic).map_err(|err| RclrsError::StringContainsNul {
101-
err,
102-
s: topic.into(),
103-
})?;
105+
let topic_c_string =
106+
CString::new(service_name).map_err(|err| RclrsError::StringContainsNul {
107+
err,
108+
s: service_name.into(),
109+
})?;
104110

105111
// SAFETY: No preconditions for this function.
106-
let client_options = unsafe { rcl_client_get_default_options() };
112+
let mut client_options = unsafe { rcl_client_get_default_options() };
113+
client_options.qos = qos.into();
107114

108115
{
109116
let rcl_node = node.handle.rcl_node.lock().unwrap();
@@ -280,6 +287,38 @@ where
280287
}
281288
}
282289

290+
/// `ClientOptions` are used by [`Node::create_client`][1] to initialize a
291+
/// [`Client`] for a service.
292+
///
293+
/// [1]: crate::Node::create_client
294+
#[derive(Debug, Clone)]
295+
#[non_exhaustive]
296+
pub struct ClientOptions<'a> {
297+
/// The name of the service that this client will send requests to
298+
pub service_name: &'a str,
299+
/// The quality of the service profile for this client
300+
pub qos: QoSProfile,
301+
}
302+
303+
impl<'a> ClientOptions<'a> {
304+
/// Initialize a new [`ClientOptions`] with default settings.
305+
pub fn new(service_name: &'a str) -> Self {
306+
Self {
307+
service_name,
308+
qos: QoSProfile::services_default(),
309+
}
310+
}
311+
}
312+
313+
impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for ClientOptions<'a> {
314+
fn from(value: T) -> Self {
315+
let primitive = value.into_primitive_options();
316+
let mut options = Self::new(primitive.name);
317+
primitive.apply_to(&mut options.qos);
318+
options
319+
}
320+
}
321+
283322
impl<T> ClientBase for Client<T>
284323
where
285324
T: rosidl_runtime_rs::Service,

0 commit comments

Comments
 (0)