Skip to content

Commit 8f564d6

Browse files
committed
fix: use vendorized messages in doctests
Signed-off-by: Esteve Fernandez <[email protected]>
1 parent c8aa3c4 commit 8f564d6

File tree

9 files changed

+39
-28
lines changed

9 files changed

+39
-28
lines changed

rclrs/src/client.rs

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -159,12 +159,10 @@ 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};
162163
/// # let node = Context::default()
163164
/// # .create_basic_executor()
164165
/// # .create_node("test_node")?;
165-
/// # The following line of code is only needed for rclrs internal purposes,
166-
/// # please use the test_msgs crate instead.
167-
/// use vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
168166
///
169167
/// async fn print_hello(_response: Empty_Response) {
170168
/// print!("Hello!");
@@ -189,13 +187,11 @@ where
189187
///
190188
/// ```
191189
/// # use rclrs::*;
190+
/// # use rclrs::vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
192191
/// # use std::future::Future;
193192
/// # let node = Context::default()
194193
/// # .create_basic_executor()
195194
/// # .create_node("test_node")?;
196-
/// # The following line of code is only needed for rclrs internal purposes,
197-
/// # please use the test_msgs crate instead.
198-
/// use vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
199195
///
200196
/// fn print_greeting(_response: Empty_Response) -> impl Future<Output=()> {
201197
/// let greeting = "Hello!";
@@ -220,12 +216,10 @@ where
220216
///
221217
/// ```
222218
/// # use rclrs::*;
219+
/// # use rclrs::vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
223220
/// # let node = Context::default()
224221
/// # .create_basic_executor()
225222
/// # .create_node("test_node")?;
226-
/// # The following line of code is only needed for rclrs internal purposes,
227-
/// # please use the test_msgs crate instead.
228-
/// use vendor::test_msgs::srv::{Empty, Empty_Request, Empty_Response};
229223
///
230224
/// let greeting = "Hello!";
231225
/// let client = node.create_client::<Empty>("my_service")?;

rclrs/src/lib.rs

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,13 +32,11 @@
3232
//!
3333
//! ```no_run
3434
//! use rclrs::*;
35+
//! use crate::rclrs::vendor::example_interfaces;
3536
//!
3637
//! let context = Context::default_from_env()?;
3738
//! let mut executor = context.create_basic_executor();
3839
//! let node = executor.create_node("example_node")?;
39-
//! # The following line of code is only needed for rclrs internal purposes,
40-
//! # please use the example_interfaces crate instead.
41-
//! use vendor::example_interfaces;
4240
//!
4341
//! let subscription = node.create_subscription(
4442
//! "topic_name",
@@ -61,7 +59,8 @@
6159
//! # let context = Context::default_from_env()?;
6260
//! # let mut executor = context.create_basic_executor();
6361
//! # let node = executor.create_node("example_node")?;
64-
//! #
62+
//! # use rclrs::vendor::example_interfaces;
63+
//!
6564
//! // This worker will manage the data for us.
6665
//! // The worker's data is called its payload.
6766
//! let worker = node.create_worker::<Option<String>>(None);
@@ -100,6 +99,8 @@
10099
//! The following is a simple example of using a mandatory parameter:
101100
//! ```no_run
102101
//! use rclrs::*;
102+
//! use rclrs::vendor::example_interfaces;
103+
//!
103104
//! use std::sync::Arc;
104105
//!
105106
//! let mut executor = Context::default_from_env()?.create_basic_executor();
@@ -129,6 +130,7 @@
129130
//!
130131
//! ```no_run
131132
//! use rclrs::*;
133+
//! use rclrs::vendor::example_interfaces;
132134
//! use std::time::Duration;
133135
//!
134136
//! let mut executor = Context::default_from_env()?.create_basic_executor();
@@ -192,7 +194,7 @@ mod service;
192194
mod subscription;
193195
mod time;
194196
mod time_source;
195-
mod vendor;
197+
pub mod vendor;
196198
mod wait_set;
197199
mod worker;
198200

rclrs/src/node.rs

Lines changed: 20 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -244,6 +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;
247248
/// let executor = Context::default().create_basic_executor();
248249
/// let node = executor.create_node("my_node").unwrap();
249250
///
@@ -269,6 +270,7 @@ impl NodeState {
269270
///
270271
/// ```
271272
/// # use rclrs::*;
273+
/// # use rclrs::vendor::example_interfaces;
272274
/// # let executor = Context::default().create_basic_executor();
273275
/// # let node = executor.create_node("my_node").unwrap();
274276
/// let worker = node.create_worker::<String>(String::new());
@@ -277,6 +279,7 @@ impl NodeState {
277279
/// The data given to the worker can be any custom data type:
278280
/// ```
279281
/// # use rclrs::*;
282+
/// # use rclrs::vendor::example_interfaces;
280283
/// # let executor = Context::default().create_basic_executor();
281284
/// # let node = executor.create_node("my_node").unwrap();
282285
///
@@ -312,6 +315,7 @@ impl NodeState {
312315
/// # use rclrs::*;
313316
/// # let executor = Context::default().create_basic_executor();
314317
/// # let node = executor.create_node("my_node").unwrap();
318+
/// # use rclrs::vendor::test_msgs;
315319
/// let client = node.create_client::<test_msgs::srv::Empty>(
316320
/// "my_service"
317321
/// )
@@ -325,6 +329,7 @@ impl NodeState {
325329
/// # use rclrs::*;
326330
/// # let executor = Context::default().create_basic_executor();
327331
/// # let node = executor.create_node("my_node").unwrap();
332+
/// # use rclrs::vendor::test_msgs;
328333
/// let client = node.create_client::<test_msgs::srv::Empty>(
329334
/// "my_service"
330335
/// .keep_all()
@@ -357,6 +362,7 @@ impl NodeState {
357362
/// # use rclrs::*;
358363
/// # let executor = Context::default().create_basic_executor();
359364
/// # let node = executor.create_node("my_node").unwrap();
365+
/// # use rclrs::vendor::test_msgs;
360366
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
361367
/// "my_topic"
362368
/// )
@@ -368,6 +374,7 @@ impl NodeState {
368374
///
369375
/// ```
370376
/// # use rclrs::*;
377+
/// # use rclrs::vendor::test_msgs;
371378
/// # let executor = Context::default().create_basic_executor();
372379
/// # let node = executor.create_node("my_node").unwrap();
373380
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
@@ -414,8 +421,10 @@ impl NodeState {
414421
/// Pass in only the service name for the `options` argument to use all default service options:
415422
/// ```
416423
/// # use rclrs::*;
424+
/// # use rclrs::vendor::test_msgs;
417425
/// # let executor = Context::default().create_basic_executor();
418426
/// # let node = executor.create_node("my_node").unwrap();
427+
///
419428
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
420429
/// "my_service",
421430
/// |_request: test_msgs::srv::Empty_Request| {
@@ -430,8 +439,10 @@ impl NodeState {
430439
///
431440
/// ```
432441
/// # use rclrs::*;
442+
/// # use rclrs::vendor::test_msgs;
433443
/// # let executor = Context::default().create_basic_executor();
434444
/// # let node = executor.create_node("my_node").unwrap();
445+
///
435446
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
436447
/// "my_service"
437448
/// .keep_all()
@@ -468,10 +479,10 @@ impl NodeState {
468479
///
469480
/// ```
470481
/// # use rclrs::*;
482+
/// # use rclrs::vendor::example_interfaces::srv::*;
471483
/// # let executor = Context::default().create_basic_executor();
472484
/// # let node = executor.create_node("my_node").unwrap();
473485
/// use std::sync::Mutex;
474-
/// use example_interfaces::srv::*;
475486
///
476487
/// let counter = Mutex::new(0usize);
477488
/// let service = node.create_service::<Trigger, _>(
@@ -494,10 +505,10 @@ impl NodeState {
494505
///
495506
/// ```
496507
/// # use rclrs::*;
508+
/// # use rclrs::vendor::example_interfaces::srv::*;
497509
/// # let executor = Context::default().create_basic_executor();
498510
/// # let node = executor.create_node("my_node").unwrap();
499511
/// use std::sync::{Arc, Mutex};
500-
/// use example_interfaces::srv::*;
501512
///
502513
/// let counter = Arc::new(Mutex::new(0usize));
503514
///
@@ -588,10 +599,10 @@ impl NodeState {
588599
///
589600
/// ```
590601
/// # use rclrs::*;
602+
/// # use rclrs::vendor::example_interfaces::srv::*;
591603
/// # let executor = Context::default().create_basic_executor();
592604
/// # let node = executor.create_node("my_node")?;
593605
/// use std::sync::Arc;
594-
/// use example_interfaces::srv::*;
595606
///
596607
/// let worker_a = node.create_worker(0_i64);
597608
/// let worker_b = node.create_worker(0_i64);
@@ -660,11 +671,9 @@ impl NodeState {
660671
/// Pass in only the topic name for the `options` argument to use all default subscription options:
661672
/// ```
662673
/// # use rclrs::*;
674+
/// # use rclrs::vendor::test_msgs;
663675
/// # let executor = Context::default().create_basic_executor();
664676
/// # let node = executor.create_node("my_node").unwrap();
665-
/// # The following line of code is only needed for rclrs internal purposes,
666-
/// # please use the test_msgs crate instead.
667-
/// use vendor::test_msgs;
668677
/// let subscription = node.create_subscription(
669678
/// "my_topic",
670679
/// |_msg: test_msgs::msg::Empty| {
@@ -678,11 +687,10 @@ impl NodeState {
678687
///
679688
/// ```
680689
/// # use rclrs::*;
690+
/// # use rclrs::vendor::test_msgs;
681691
/// # let executor = Context::default().create_basic_executor();
682692
/// # let node = executor.create_node("my_node").unwrap();
683693
/// # The following line of code is only needed for rclrs internal purposes,
684-
/// # please use the test_msgs crate instead.
685-
/// use vendor::test_msgs;
686694
/// let subscription = node.create_subscription(
687695
/// "my_topic"
688696
/// .keep_last(100)
@@ -723,6 +731,7 @@ impl NodeState {
723731
///
724732
/// ```
725733
/// # use rclrs::*;
734+
/// # use rclrs::vendor::example_interfaces;
726735
/// # let executor = Context::default().create_basic_executor();
727736
/// # let node = executor.create_node("my_node").unwrap();
728737
/// use std::sync::Mutex;
@@ -745,6 +754,7 @@ impl NodeState {
745754
///
746755
/// ```
747756
/// # use rclrs::*;
757+
/// # use rclrs::vendor::example_interfaces;
748758
/// # let executor = Context::default().create_basic_executor();
749759
/// # let node = executor.create_node("my_node").unwrap();
750760
/// use std::sync::{Arc, Mutex};
@@ -845,8 +855,10 @@ impl NodeState {
845855
///
846856
/// ```
847857
/// # use rclrs::*;
858+
/// # use rclrs::vendor::example_interfaces;
848859
/// # let executor = Context::default().create_basic_executor();
849860
/// # let node = executor.create_node("my_node").unwrap();
861+
///
850862
/// use std::sync::Arc;
851863
///
852864
/// let count_worker = node.create_worker(0_usize);

rclrs/src/publisher.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -344,8 +344,8 @@ mod tests {
344344

345345
#[test]
346346
fn test_publishers() -> Result<(), RclrsError> {
347-
use crate::TopicEndpointInfo;
348347
use crate::vendor::test_msgs::msg;
348+
use crate::TopicEndpointInfo;
349349

350350
let namespace = "/test_publishers_graph";
351351
let graph = construct_test_graph(namespace)?;

rclrs/src/service.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -400,8 +400,8 @@ mod tests {
400400

401401
#[test]
402402
fn test_services() -> Result<(), RclrsError> {
403-
use crate::TopicNamesAndTypes;
404403
use crate::vendor::test_msgs::srv;
404+
use crate::TopicNamesAndTypes;
405405

406406
let namespace = "/test_services_graph";
407407
let graph = construct_test_graph(namespace)?;

rclrs/src/subscription.rs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -523,8 +523,8 @@ mod tests {
523523

524524
#[test]
525525
fn test_delayed_subscription() {
526-
use crate::*;
527526
use crate::vendor::example_interfaces::msg::Empty;
527+
use crate::*;
528528
use futures::{
529529
channel::{mpsc, oneshot},
530530
StreamExt,

rclrs/src/vendor/mod.rs

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
//! Created by vendor_interfaces.py
22
#![allow(dead_code)]
3+
#![allow(missing_docs)]
34

45
pub mod action_msgs;
56
pub mod builtin_interfaces;

rclrs/src/worker.rs

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -228,6 +228,7 @@ impl<Payload: 'static + Send + Sync> WorkerState<Payload> {
228228
///
229229
/// ```
230230
/// # use rclrs::*;
231+
/// # use rclrs::vendor::example_interfaces;
231232
/// # let executor = Context::default().create_basic_executor();
232233
/// # let node = executor.create_node("my_node").unwrap();
233234
/// // The worker's payload is data that we want to share with other callbacks.
@@ -320,9 +321,9 @@ impl<Payload: 'static + Send + Sync> WorkerState<Payload> {
320321
///
321322
/// ```
322323
/// # use rclrs::*;
324+
/// # use rclrs::vendor::example_interfaces::srv::*;
323325
/// # let executor = Context::default().create_basic_executor();
324326
/// # let node = executor.create_node("my_node").unwrap();
325-
/// use example_interfaces::srv::*;
326327
///
327328
/// /// Store the operands of the service request for later reference
328329
/// #[derive(Default)]
@@ -500,12 +501,12 @@ impl<Payload: 'static + Send + Sync> WorkScope for Worker<Payload> {
500501

501502
#[cfg(test)]
502503
mod tests {
503-
use crate::*;
504-
use std::time::Duration;
505504
use crate::vendor::test_msgs::{
506505
msg::Empty as EmptyMsg,
507506
srv::{Empty as EmptySrv, Empty_Request, Empty_Response},
508507
};
508+
use crate::*;
509+
use std::time::Duration;
509510

510511
#[derive(Default, Clone, Copy, Debug)]
511512
struct TestPayload {

rclrs/vendor_interfaces.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ def main():
6363

6464
mod_contents = "//! Created by {}\n".format(Path(__file__).name)
6565
mod_contents += "#![allow(dead_code)]\n"
66+
mod_contents += "#![allow(missing_docs)]\n"
6667
mod_contents += "\n"
6768
for pkg in vendored_packages:
6869
mod_contents += f"pub mod {pkg};\n"

0 commit comments

Comments
 (0)