Skip to content

Commit f0749d8

Browse files
committed
fix: cleanups
Signed-off-by: Esteve Fernandez <[email protected]>
1 parent d572918 commit f0749d8

File tree

4 files changed

+53
-56
lines changed

4 files changed

+53
-56
lines changed

rclrs/src/client.rs

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -159,17 +159,17 @@ where
159159
/// signatures and which returns a `()` (a.k.a. nothing).
160160
/// ```
161161
/// # use rclrs::*;
162-
/// # use rclrs::vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
162+
/// # use crate::rclrs::vendor::test_msgs;
163163
/// # let node = Context::default()
164164
/// # .create_basic_executor()
165165
/// # .create_node("test_node")?;
166166
///
167-
/// async fn print_hello(_response: Empty_Response) {
167+
/// async fn print_hello(_response: test_msgs::srv::Empty_Response) {
168168
/// print!("Hello!");
169169
/// }
170170
///
171-
/// let client = node.create_client::<Empty>("my_service")?;
172-
/// let request = Empty_Request::default();
171+
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
172+
/// let request = test_msgs::srv::Empty_Request::default();
173173
/// let promise = client.call_then_async(&request, print_hello)?;
174174
/// # Ok::<(), RclrsError>(())
175175
/// ```
@@ -187,21 +187,21 @@ where
187187
///
188188
/// ```
189189
/// # use rclrs::*;
190-
/// # use rclrs::vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
190+
/// # use crate::rclrs::vendor::test_msgs;
191191
/// # use std::future::Future;
192192
/// # let node = Context::default()
193193
/// # .create_basic_executor()
194194
/// # .create_node("test_node")?;
195195
///
196-
/// fn print_greeting(_response: Empty_Response) -> impl Future<Output=()> {
196+
/// fn print_greeting(_response: test_msgs::srv::Empty_Response) -> impl Future<Output=()> {
197197
/// let greeting = "Hello!";
198198
/// async move {
199199
/// print!("Hello!");
200200
/// }
201201
/// }
202202
///
203-
/// let client = node.create_client::<Empty>("my_service")?;
204-
/// let request = Empty_Request::default();
203+
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
204+
/// let request = test_msgs::srv::Empty_Request::default();
205205
/// let promise = client.call_then_async(
206206
/// &request,
207207
/// print_greeting)?;
@@ -216,17 +216,17 @@ where
216216
///
217217
/// ```
218218
/// # use rclrs::*;
219-
/// # use rclrs::vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
219+
/// # use crate::rclrs::vendor::test_msgs;
220220
/// # let node = Context::default()
221221
/// # .create_basic_executor()
222222
/// # .create_node("test_node")?;
223223
///
224224
/// let greeting = "Hello!";
225-
/// let client = node.create_client::<Empty>("my_service")?;
226-
/// let request = Empty_Request::default();
225+
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
226+
/// let request = test_msgs::srv::Empty_Request::default();
227227
/// let promise = client.call_then_async(
228228
/// &request,
229-
/// move |response: Empty_Response| {
229+
/// move |response: test_msgs::srv::Empty_Response| {
230230
/// async move {
231231
/// print!("{greeting}");
232232
/// }
@@ -568,12 +568,12 @@ unsafe impl Send for rcl_client_t {}
568568
mod tests {
569569
use super::*;
570570
use crate::test_helpers::*;
571-
use crate::vendor::test_msgs::srv;
571+
use crate::vendor::test_msgs;
572572

573573
#[test]
574574
fn traits() {
575-
assert_send::<Client<srv::Arrays>>();
576-
assert_sync::<Client<srv::Arrays>>();
575+
assert_send::<Client<test_msgs::srv::Arrays>>();
576+
assert_sync::<Client<test_msgs::srv::Arrays>>();
577577
}
578578

579579
#[test]
@@ -582,7 +582,7 @@ mod tests {
582582
let graph = construct_test_graph(namespace)?;
583583
let _node_2_empty_client = graph
584584
.node2
585-
.create_client::<srv::Empty>("graph_test_topic_4")?;
585+
.create_client::<test_msgs::srv::Empty>("graph_test_topic_4")?;
586586

587587
std::thread::sleep(std::time::Duration::from_millis(200));
588588

rclrs/src/lib.rs

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
//!
3333
//! ```no_run
3434
//! use rclrs::*;
35-
//! use crate::rclrs::vendor::example_interfaces;
35+
//! # use crate::rclrs::vendor::example_interfaces;
3636
//!
3737
//! let context = Context::default_from_env()?;
3838
//! let mut executor = context.create_basic_executor();
@@ -59,8 +59,8 @@
5959
//! # let context = Context::default_from_env()?;
6060
//! # let mut executor = context.create_basic_executor();
6161
//! # let node = executor.create_node("example_node")?;
62-
//! # use rclrs::vendor::example_interfaces;
63-
//!
62+
//! # use crate::rclrs::vendor::example_interfaces;
63+
//! #
6464
//! // This worker will manage the data for us.
6565
//! // The worker's data is called its payload.
6666
//! let worker = node.create_worker::<Option<String>>(None);
@@ -99,8 +99,7 @@
9999
//! The following is a simple example of using a mandatory parameter:
100100
//! ```no_run
101101
//! use rclrs::*;
102-
//! use rclrs::vendor::example_interfaces;
103-
//!
102+
//! # use crate::rclrs::vendor::example_interfaces;
104103
//! use std::sync::Arc;
105104
//!
106105
//! let mut executor = Context::default_from_env()?.create_basic_executor();
@@ -130,7 +129,7 @@
130129
//!
131130
//! ```no_run
132131
//! use rclrs::*;
133-
//! use rclrs::vendor::example_interfaces;
132+
//! # use crate::rclrs::vendor::example_interfaces;
134133
//! use std::time::Duration;
135134
//!
136135
//! let mut executor = Context::default_from_env()?.create_basic_executor();

rclrs/src/node.rs

Lines changed: 26 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -244,7 +244,7 @@ impl NodeState {
244244
/// In some cases the payload type can be inferred by Rust:
245245
/// ```
246246
/// # use rclrs::*;
247-
/// # use rclrs::vendor::example_interfaces;
247+
/// # use crate::rclrs::vendor::example_interfaces;
248248
/// let executor = Context::default().create_basic_executor();
249249
/// let node = executor.create_node("my_node").unwrap();
250250
///
@@ -270,7 +270,7 @@ impl NodeState {
270270
///
271271
/// ```
272272
/// # use rclrs::*;
273-
/// # use rclrs::vendor::example_interfaces;
273+
/// # use crate::rclrs::vendor::example_interfaces;
274274
/// # let executor = Context::default().create_basic_executor();
275275
/// # let node = executor.create_node("my_node").unwrap();
276276
/// let worker = node.create_worker::<String>(String::new());
@@ -279,7 +279,7 @@ impl NodeState {
279279
/// The data given to the worker can be any custom data type:
280280
/// ```
281281
/// # use rclrs::*;
282-
/// # use rclrs::vendor::example_interfaces;
282+
/// # use crate::rclrs::vendor::example_interfaces;
283283
/// # let executor = Context::default().create_basic_executor();
284284
/// # let node = executor.create_node("my_node").unwrap();
285285
///
@@ -315,7 +315,7 @@ impl NodeState {
315315
/// # use rclrs::*;
316316
/// # let executor = Context::default().create_basic_executor();
317317
/// # let node = executor.create_node("my_node").unwrap();
318-
/// # use rclrs::vendor::test_msgs;
318+
/// # use crate::rclrs::vendor::test_msgs;
319319
/// let client = node.create_client::<test_msgs::srv::Empty>(
320320
/// "my_service"
321321
/// )
@@ -329,7 +329,7 @@ impl NodeState {
329329
/// # use rclrs::*;
330330
/// # let executor = Context::default().create_basic_executor();
331331
/// # let node = executor.create_node("my_node").unwrap();
332-
/// # use rclrs::vendor::test_msgs;
332+
/// # use crate::rclrs::vendor::test_msgs;
333333
/// let client = node.create_client::<test_msgs::srv::Empty>(
334334
/// "my_service"
335335
/// .keep_all()
@@ -362,7 +362,7 @@ impl NodeState {
362362
/// # use rclrs::*;
363363
/// # let executor = Context::default().create_basic_executor();
364364
/// # let node = executor.create_node("my_node").unwrap();
365-
/// # use rclrs::vendor::test_msgs;
365+
/// # use crate::rclrs::vendor::test_msgs;
366366
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
367367
/// "my_topic"
368368
/// )
@@ -374,7 +374,7 @@ impl NodeState {
374374
///
375375
/// ```
376376
/// # use rclrs::*;
377-
/// # use rclrs::vendor::test_msgs;
377+
/// # use crate::rclrs::vendor::test_msgs;
378378
/// # let executor = Context::default().create_basic_executor();
379379
/// # let node = executor.create_node("my_node").unwrap();
380380
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
@@ -421,10 +421,9 @@ impl NodeState {
421421
/// Pass in only the service name for the `options` argument to use all default service options:
422422
/// ```
423423
/// # use rclrs::*;
424-
/// # use rclrs::vendor::test_msgs;
424+
/// # use crate::rclrs::vendor::test_msgs;
425425
/// # let executor = Context::default().create_basic_executor();
426426
/// # let node = executor.create_node("my_node").unwrap();
427-
///
428427
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
429428
/// "my_service",
430429
/// |_request: test_msgs::srv::Empty_Request| {
@@ -439,10 +438,9 @@ impl NodeState {
439438
///
440439
/// ```
441440
/// # use rclrs::*;
442-
/// # use rclrs::vendor::test_msgs;
441+
/// # use crate::rclrs::vendor::test_msgs;
443442
/// # let executor = Context::default().create_basic_executor();
444443
/// # let node = executor.create_node("my_node").unwrap();
445-
///
446444
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
447445
/// "my_service"
448446
/// .keep_all()
@@ -479,19 +477,19 @@ impl NodeState {
479477
///
480478
/// ```
481479
/// # use rclrs::*;
482-
/// # use rclrs::vendor::example_interfaces::srv::*;
480+
/// # use crate::rclrs::vendor::example_interfaces;
483481
/// # let executor = Context::default().create_basic_executor();
484482
/// # let node = executor.create_node("my_node").unwrap();
485483
/// use std::sync::Mutex;
486484
///
487485
/// let counter = Mutex::new(0usize);
488-
/// let service = node.create_service::<Trigger, _>(
486+
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
489487
/// "trigger_counter",
490-
/// move |_request: Trigger_Request| {
488+
/// move |_request: example_interfaces::srv::Trigger_Request| {
491489
/// let mut counter = counter.lock().unwrap();
492490
/// *counter += 1;
493491
/// println!("Triggered {} times", *counter);
494-
/// Trigger_Response {
492+
/// example_interfaces::srv::Trigger_Response {
495493
/// success: true,
496494
/// message: "no problems here".to_string(),
497495
/// }
@@ -505,21 +503,21 @@ impl NodeState {
505503
///
506504
/// ```
507505
/// # use rclrs::*;
508-
/// # use rclrs::vendor::example_interfaces::srv::*;
506+
/// # use crate::rclrs::vendor::example_interfaces;
509507
/// # let executor = Context::default().create_basic_executor();
510508
/// # let node = executor.create_node("my_node").unwrap();
511509
/// use std::sync::{Arc, Mutex};
512510
///
513511
/// let counter = Arc::new(Mutex::new(0usize));
514512
///
515513
/// let counter_in_service = Arc::clone(&counter);
516-
/// let service = node.create_service::<Trigger, _>(
514+
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
517515
/// "trigger_counter",
518-
/// move |_request: Trigger_Request| {
516+
/// move |_request: example_interfaces::srv::Trigger_Request| {
519517
/// let mut counter = counter_in_service.lock().unwrap();
520518
/// *counter += 1;
521519
/// println!("Triggered {} times", *counter);
522-
/// Trigger_Response {
520+
/// example_interfaces::srv::Trigger_Response {
523521
/// success: true,
524522
/// message: "no problems here".to_string(),
525523
/// }
@@ -599,17 +597,17 @@ impl NodeState {
599597
///
600598
/// ```
601599
/// # use rclrs::*;
602-
/// # use rclrs::vendor::example_interfaces::srv::*;
600+
/// # use crate::rclrs::vendor::example_interfaces;
603601
/// # let executor = Context::default().create_basic_executor();
604602
/// # let node = executor.create_node("my_node")?;
605603
/// use std::sync::Arc;
606604
///
607605
/// let worker_a = node.create_worker(0_i64);
608606
/// let worker_b = node.create_worker(0_i64);
609607
///
610-
/// let service = node.create_async_service::<AddTwoInts, _>(
608+
/// let service = node.create_async_service::<example_interfaces::srv::AddTwoInts, _>(
611609
/// "add",
612-
/// move |request: AddTwoInts_Request| {
610+
/// move |request: example_interfaces::srv::AddTwoInts_Request| {
613611
/// // Clone the workers so they can be captured into the async block
614612
/// let worker_a = Arc::clone(&worker_a);
615613
/// let worker_b = Arc::clone(&worker_b);
@@ -628,7 +626,7 @@ impl NodeState {
628626
/// // Awaiting above ensures that each number from the
629627
/// // request is saved in its respective worker before
630628
/// // we give back a response.
631-
/// AddTwoInts_Response { sum: a + b }
629+
/// example_interfaces::srv::AddTwoInts_Response { sum: a + b }
632630
/// }
633631
/// }
634632
/// )?;
@@ -671,7 +669,7 @@ impl NodeState {
671669
/// Pass in only the topic name for the `options` argument to use all default subscription options:
672670
/// ```
673671
/// # use rclrs::*;
674-
/// # use rclrs::vendor::test_msgs;
672+
/// # use crate::rclrs::vendor::test_msgs;
675673
/// # let executor = Context::default().create_basic_executor();
676674
/// # let node = executor.create_node("my_node").unwrap();
677675
/// let subscription = node.create_subscription(
@@ -687,7 +685,7 @@ impl NodeState {
687685
///
688686
/// ```
689687
/// # use rclrs::*;
690-
/// # use rclrs::vendor::test_msgs;
688+
/// # use crate::rclrs::vendor::test_msgs;
691689
/// # let executor = Context::default().create_basic_executor();
692690
/// # let node = executor.create_node("my_node").unwrap();
693691
/// let subscription = node.create_subscription(
@@ -730,7 +728,7 @@ impl NodeState {
730728
///
731729
/// ```
732730
/// # use rclrs::*;
733-
/// # use rclrs::vendor::example_interfaces;
731+
/// # use crate::rclrs::vendor::example_interfaces;
734732
/// # let executor = Context::default().create_basic_executor();
735733
/// # let node = executor.create_node("my_node").unwrap();
736734
/// use std::sync::Mutex;
@@ -753,7 +751,7 @@ impl NodeState {
753751
///
754752
/// ```
755753
/// # use rclrs::*;
756-
/// # use rclrs::vendor::example_interfaces;
754+
/// # use crate::rclrs::vendor::example_interfaces;
757755
/// # let executor = Context::default().create_basic_executor();
758756
/// # let node = executor.create_node("my_node").unwrap();
759757
/// use std::sync::{Arc, Mutex};
@@ -854,7 +852,7 @@ impl NodeState {
854852
///
855853
/// ```
856854
/// # use rclrs::*;
857-
/// # use rclrs::vendor::example_interfaces;
855+
/// # use crate::rclrs::vendor::example_interfaces;
858856
/// # let executor = Context::default().create_basic_executor();
859857
/// # let node = executor.create_node("my_node").unwrap();
860858
///

rclrs/src/worker.rs

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -228,7 +228,7 @@ impl<Payload: 'static + Send + Sync> WorkerState<Payload> {
228228
///
229229
/// ```
230230
/// # use rclrs::*;
231-
/// # use rclrs::vendor::example_interfaces;
231+
/// # use crate::rclrs::vendor::example_interfaces;
232232
/// # let executor = Context::default().create_basic_executor();
233233
/// # let node = executor.create_node("my_node").unwrap();
234234
/// // The worker's payload is data that we want to share with other callbacks.
@@ -321,7 +321,7 @@ impl<Payload: 'static + Send + Sync> WorkerState<Payload> {
321321
///
322322
/// ```
323323
/// # use rclrs::*;
324-
/// # use rclrs::vendor::example_interfaces::srv::*;
324+
/// # use crate::rclrs::vendor::example_interfaces;
325325
/// # let executor = Context::default().create_basic_executor();
326326
/// # let node = executor.create_node("my_node").unwrap();
327327
///
@@ -339,17 +339,17 @@ impl<Payload: 'static + Send + Sync> WorkerState<Payload> {
339339
/// // callback.
340340
/// let mut count = 0_usize;
341341
///
342-
/// let service = worker.create_service::<AddTwoInts, _>(
342+
/// let service = worker.create_service::<example_interfaces::srv::AddTwoInts, _>(
343343
/// "add",
344-
/// move |payload: &mut Operands, request: AddTwoInts_Request| {
344+
/// move |payload: &mut Operands, request: example_interfaces::srv::AddTwoInts_Request| {
345345
/// count += 1;
346-
/// let AddTwoInts_Request { a, b } = request;
346+
/// let example_interfaces::srv::AddTwoInts_Request { a, b } = request;
347347
/// let sum = a + b;
348348
/// println!("#{count} | {a} + {b} = {sum}");
349349
///
350350
/// *payload = Operands { a, b };
351351
///
352-
/// AddTwoInts_Response { sum }
352+
/// example_interfaces::srv::AddTwoInts_Response { sum }
353353
/// }
354354
/// )?;
355355
/// # Ok::<(), RclrsError>(())

0 commit comments

Comments
 (0)