Skip to content

Commit 2a7ff60

Browse files
committed
Merge options pattern PR
Signed-off-by: Michael X. Grey <[email protected]>
2 parents f1c4716 + 98b8ea2 commit 2a7ff60

38 files changed

+1173
-808
lines changed

examples/message_demo/src/message_demo.rs

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -141,25 +141,19 @@ fn demonstrate_pubsub() -> Result<(), Error> {
141141
let mut executor = rclrs::Context::default_from_env()?.create_basic_executor();
142142
let node = executor.create_node("message_demo")?;
143143

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

153149
let _idiomatic_subscription = node
154150
.create_subscription::<rclrs_example_msgs::msg::VariousTypes, _>(
155151
"topic",
156-
rclrs::QOS_PROFILE_DEFAULT,
157152
move |_msg: rclrs_example_msgs::msg::VariousTypes| println!("Got idiomatic message!"),
158153
)?;
159154
let _direct_subscription = node
160155
.create_subscription::<rclrs_example_msgs::msg::rmw::VariousTypes, _>(
161156
"topic",
162-
rclrs::QOS_PROFILE_DEFAULT,
163157
move |_msg: rclrs_example_msgs::msg::rmw::VariousTypes| {
164158
println!("Got RMW-native message!")
165159
},

examples/minimal_pub_sub/src/minimal_publisher.rs

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,7 @@ fn main() -> Result<(), Error> {
66

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

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

1211
let mut message = std_msgs::msg::String::default();
1312

examples/minimal_pub_sub/src/minimal_subscriber.rs

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

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

examples/minimal_pub_sub/src/minimal_two_nodes.rs

Lines changed: 1 addition & 3 deletions
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
},
@@ -58,8 +57,7 @@ fn main() -> Result<(), Error> {
5857
let _subscriber_node_two =
5958
MinimalSubscriber::new(&executor, "minimal_subscriber_two", "topic")?;
6059

61-
let publisher = publisher_node
62-
.create_publisher::<std_msgs::msg::String>("topic", rclrs::QOS_PROFILE_DEFAULT)?;
60+
let publisher = publisher_node.create_publisher::<std_msgs::msg::String>("topic")?;
6361

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

examples/minimal_pub_sub/src/zero_copy_publisher.rs

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,7 @@ fn main() -> Result<(), Error> {
66

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

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

1211
let mut publish_count: u32 = 1;
1312

examples/minimal_pub_sub/src/zero_copy_subscriber.rs

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

1010
let _subscription = node.create_subscription::<std_msgs::msg::UInt32, _>(
1111
"topic",
12-
rclrs::QOS_PROFILE_DEFAULT,
1312
move |msg: rclrs::ReadOnlyLoanedMessage<'_, std_msgs::msg::UInt32>| {
1413
num_messages += 1;
1514
println!("I heard: '{}'", msg.data);

examples/rust_pubsub/src/simple_publisher.rs

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,15 @@ use rclrs::{Context, Executor, Publisher, RclrsError, SpinOptions, QOS_PROFILE_D
22
use std::{sync::Arc, thread, time::Duration};
33
use std_msgs::msg::String as StringMsg;
44

5-
struct SimplePublisher {
5+
struct SimplePublisherNode {
66
publisher: Arc<Publisher<StringMsg>>,
77
}
88

9-
impl SimplePublisher {
9+
impl SimplePublisherNode {
1010
fn new(executor: &Executor) -> Result<Self, RclrsError> {
1111
let node = executor.create_node("simple_publisher").unwrap();
1212
let publisher = node
13-
.create_publisher("publish_hello", QOS_PROFILE_DEFAULT)
13+
.create_publisher("publish_hello")
1414
.unwrap();
1515
Ok(Self { publisher })
1616
}

examples/rust_pubsub/src/simple_subscriber.rs

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -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/client.rs

Lines changed: 64 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,15 @@
11
use std::{
2+
collections::HashMap,
23
ffi::CString,
34
sync::{Arc, Mutex, MutexGuard},
4-
collections::HashMap,
55
};
66

77
use rosidl_runtime_rs::Message;
88

99
use crate::{
10-
error::ToResult,
11-
rcl_bindings::*,
12-
MessageCow, Node, RclrsError, RclReturnCode, Promise, ENTITY_LIFECYCLE_MUTEX,
13-
RclPrimitive, QoSProfile, Waitable, WaitableLifecycle,
14-
RclPrimitiveHandle, RclPrimitiveKind, ServiceInfo,
10+
error::ToResult, rcl_bindings::*, IntoPrimitiveOptions, MessageCow, Node, Promise, QoSProfile,
11+
RclPrimitive, RclPrimitiveHandle, RclPrimitiveKind, RclReturnCode, RclrsError, ServiceInfo,
12+
Waitable, WaitableLifecycle, ENTITY_LIFECYCLE_MUTEX,
1513
};
1614

1715
mod client_async_callback;
@@ -59,10 +57,7 @@ where
5957
///
6058
/// [1]: crate::RequestId
6159
/// [2]: crate::ServiceInfo
62-
pub fn call<'a, Req, Out>(
63-
&self,
64-
request: Req,
65-
) -> Result<Promise<Out>, RclrsError>
60+
pub fn call<'a, Req, Out>(&self, request: Req) -> Result<Promise<Out>, RclrsError>
6661
where
6762
Req: MessageCow<'a, T::Request>,
6863
Out: ClientOutput<T::Response>,
@@ -82,7 +77,10 @@ where
8277
.ok()?;
8378

8479
// TODO(@mxgrey): Log errors here when logging becomes available.
85-
self.board.lock().unwrap().new_request(sequence_number, sender);
80+
self.board
81+
.lock()
82+
.unwrap()
83+
.new_request(sequence_number, sender);
8684

8785
Ok(promise)
8886
}
@@ -103,8 +101,8 @@ where
103101
where
104102
Req: MessageCow<'a, T::Request>,
105103
{
106-
let callback = move |response, info| {
107-
async { callback.run_client_callback(response, info); }
104+
let callback = move |response, info| async {
105+
callback.run_client_callback(response, info);
108106
};
109107
self.call_then_async(request, callback)
110108
}
@@ -167,29 +165,30 @@ where
167165
let client = Arc::clone(self);
168166
self.handle.node.notify_on_graph_change(
169167
// TODO(@mxgrey): Log any errors here once logging is available
170-
move || client.service_is_ready().is_ok_and(|r| r)
168+
move || client.service_is_ready().is_ok_and(|r| r),
171169
)
172170
}
173171

174172
/// Creates a new client.
175-
pub(crate) fn create(
176-
topic: &str,
177-
qos: QoSProfile,
173+
pub(crate) fn create<'a>(
178174
node: &Arc<Node>,
175+
options: impl Into<ClientOptions<'a>>,
179176
) -> Result<Arc<Self>, RclrsError>
180177
// This uses pub(crate) visibility to avoid instantiating this struct outside
181178
// [`Node::create_client`], see the struct's documentation for the rationale
182179
where
183180
T: rosidl_runtime_rs::Service,
184181
{
182+
let ClientOptions { service_name, qos } = options.into();
185183
// SAFETY: Getting a zero-initialized value is always safe.
186184
let mut rcl_client = unsafe { rcl_get_zero_initialized_client() };
187185
let type_support = <T as rosidl_runtime_rs::Service>::get_type_support()
188186
as *const rosidl_service_type_support_t;
189-
let topic_c_string = CString::new(topic).map_err(|err| RclrsError::StringContainsNul {
190-
err,
191-
s: topic.into(),
192-
})?;
187+
let topic_c_string =
188+
CString::new(service_name).map_err(|err| RclrsError::StringContainsNul {
189+
err,
190+
s: service_name.into(),
191+
})?;
193192

194193
// SAFETY: No preconditions for this function.
195194
let mut client_options = unsafe { rcl_client_get_default_options() };
@@ -243,12 +242,44 @@ where
243242
}
244243
}
245244

245+
/// `ClientOptions` are used by [`Node::create_client`][1] to initialize a
246+
/// [`Client`] for a service.
247+
///
248+
/// [1]: crate::Node::create_client
249+
#[derive(Debug, Clone)]
250+
#[non_exhaustive]
251+
pub struct ClientOptions<'a> {
252+
/// The name of the service that this client will send requests to
253+
pub service_name: &'a str,
254+
/// The quality of the service profile for this client
255+
pub qos: QoSProfile,
256+
}
257+
258+
impl<'a> ClientOptions<'a> {
259+
/// Initialize a new [`ClientOptions`] with default settings.
260+
pub fn new(service_name: &'a str) -> Self {
261+
Self {
262+
service_name,
263+
qos: QoSProfile::services_default(),
264+
}
265+
}
266+
}
267+
268+
impl<'a, T: IntoPrimitiveOptions<'a>> From<T> for ClientOptions<'a> {
269+
fn from(value: T) -> Self {
270+
let primitive = value.into_primitive_options();
271+
let mut options = Self::new(primitive.name);
272+
primitive.apply(&mut options.qos);
273+
options
274+
}
275+
}
276+
246277
struct ClientExecutable<T>
247278
where
248279
T: rosidl_runtime_rs::Service,
249280
{
250281
handle: Arc<ClientHandle>,
251-
board: Arc<Mutex<ClientRequestBoard<T>>>
282+
board: Arc<Mutex<ClientRequestBoard<T>>>,
252283
}
253284

254285
impl<T> RclPrimitive for ClientExecutable<T>
@@ -326,7 +357,10 @@ where
326357
}
327358
Err(err) => {
328359
match err {
329-
RclrsError::RclError { code: RclReturnCode::ClientTakeFailed, .. } => {
360+
RclrsError::RclError {
361+
code: RclReturnCode::ClientTakeFailed,
362+
..
363+
} => {
330364
// This is okay, it means a spurious wakeup happened
331365
}
332366
err => {
@@ -355,10 +389,12 @@ where
355389
)
356390
}
357391
.ok()
358-
.map(|_| (
359-
T::Response::from_rmw_message(response_out),
360-
service_info_out,
361-
))
392+
.map(|_| {
393+
(
394+
T::Response::from_rmw_message(response_out),
395+
service_info_out,
396+
)
397+
})
362398
}
363399
}
364400

@@ -415,7 +451,7 @@ mod tests {
415451
let graph = construct_test_graph(namespace)?;
416452
let _node_2_empty_client = graph
417453
.node2
418-
.create_client::<srv::Empty>("graph_test_topic_4", QoSProfile::services_default())?;
454+
.create_client::<srv::Empty>("graph_test_topic_4")?;
419455

420456
std::thread::sleep(std::time::Duration::from_millis(200));
421457

rclrs/src/client/client_async_callback.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ use rosidl_runtime_rs::Service;
22

33
use std::future::Future;
44

5-
use crate::{ServiceInfo, RequestId};
5+
use crate::{RequestId, ServiceInfo};
66

77
/// A trait to deduce async callbacks of service clients.
88
///

0 commit comments

Comments
 (0)