Skip to content

Commit 75cd88e

Browse files
authored
feat: vendorize messages so that cargo update works (#509)
* feat: vendorize messages so that cargo update works Signed-off-by: Esteve Fernandez <[email protected]> * fix: added extra vendorized messages Signed-off-by: Esteve Fernandez <[email protected]> * fix: use vendorized messages in doctests Signed-off-by: Esteve Fernandez <[email protected]> * fix: remove leftover line Signed-off-by: Esteve Fernandez <[email protected]> * fix: cleanups Signed-off-by: Esteve Fernandez <[email protected]> --------- Signed-off-by: Esteve Fernandez <[email protected]>
1 parent 5ea1c95 commit 75cd88e

24 files changed

+14502
-48
lines changed

rclrs/Cargo.toml

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,6 @@ serde-big-array = { version = "0.5.1", optional = true }
3939
[dev-dependencies]
4040
# Needed for e.g. writing yaml files in tests
4141
tempfile = "3.3.0"
42-
# Needed for publisher and subscriber tests
43-
test_msgs = {version = "*"}
44-
# Used in doctests
45-
example_interfaces = { version = "*" }
4642
# Needed for parameter service tests
4743
tokio = { version = "1", features = ["rt", "time", "macros"] }
4844

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 crate::rclrs::vendor::test_msgs;
162163
/// # let node = Context::default()
163164
/// # .create_basic_executor()
164165
/// # .create_node("test_node")?;
165-
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
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 crate::rclrs::vendor::test_msgs;
190191
/// # use std::future::Future;
191192
/// # let node = Context::default()
192193
/// # .create_basic_executor()
193194
/// # .create_node("test_node")?;
194-
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
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 crate::rclrs::vendor::test_msgs;
219220
/// # let node = Context::default()
220221
/// # .create_basic_executor()
221222
/// # .create_node("test_node")?;
222-
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
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 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 & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
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();
@@ -58,6 +59,7 @@
5859
//! # let context = Context::default_from_env()?;
5960
//! # let mut executor = context.create_basic_executor();
6061
//! # let node = executor.create_node("example_node")?;
62+
//! # use crate::rclrs::vendor::example_interfaces;
6163
//! #
6264
//! // This worker will manage the data for us.
6365
//! // The worker's data is called its payload.
@@ -97,6 +99,7 @@
9799
//! The following is a simple example of using a mandatory parameter:
98100
//! ```no_run
99101
//! use rclrs::*;
102+
//! # use crate::rclrs::vendor::example_interfaces;
100103
//! use std::sync::Arc;
101104
//!
102105
//! let mut executor = Context::default_from_env()?.create_basic_executor();
@@ -126,6 +129,7 @@
126129
//!
127130
//! ```no_run
128131
//! use rclrs::*;
132+
//! # use crate::rclrs::vendor::example_interfaces;
129133
//! use std::time::Duration;
130134
//!
131135
//! let mut executor = Context::default_from_env()?.create_basic_executor();
@@ -189,7 +193,7 @@ mod service;
189193
mod subscription;
190194
mod time;
191195
mod time_source;
192-
mod vendor;
196+
pub mod vendor;
193197
mod wait_set;
194198
mod worker;
195199

rclrs/src/node.rs

Lines changed: 28 additions & 13 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 crate::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 crate::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 crate::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 crate::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 crate::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 crate::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 crate::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,6 +421,7 @@ 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 crate::rclrs::vendor::test_msgs;
417425
/// # let executor = Context::default().create_basic_executor();
418426
/// # let node = executor.create_node("my_node").unwrap();
419427
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
@@ -430,6 +438,7 @@ impl NodeState {
430438
///
431439
/// ```
432440
/// # use rclrs::*;
441+
/// # use crate::rclrs::vendor::test_msgs;
433442
/// # let executor = Context::default().create_basic_executor();
434443
/// # let node = executor.create_node("my_node").unwrap();
435444
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
@@ -468,19 +477,19 @@ impl NodeState {
468477
///
469478
/// ```
470479
/// # use rclrs::*;
480+
/// # use crate::rclrs::vendor::example_interfaces;
471481
/// # let executor = Context::default().create_basic_executor();
472482
/// # let node = executor.create_node("my_node").unwrap();
473483
/// use std::sync::Mutex;
474-
/// use example_interfaces::srv::*;
475484
///
476485
/// let counter = Mutex::new(0usize);
477-
/// let service = node.create_service::<Trigger, _>(
486+
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
478487
/// "trigger_counter",
479-
/// move |_request: Trigger_Request| {
488+
/// move |_request: example_interfaces::srv::Trigger_Request| {
480489
/// let mut counter = counter.lock().unwrap();
481490
/// *counter += 1;
482491
/// println!("Triggered {} times", *counter);
483-
/// Trigger_Response {
492+
/// example_interfaces::srv::Trigger_Response {
484493
/// success: true,
485494
/// message: "no problems here".to_string(),
486495
/// }
@@ -494,21 +503,21 @@ impl NodeState {
494503
///
495504
/// ```
496505
/// # use rclrs::*;
506+
/// # use crate::rclrs::vendor::example_interfaces;
497507
/// # let executor = Context::default().create_basic_executor();
498508
/// # let node = executor.create_node("my_node").unwrap();
499509
/// use std::sync::{Arc, Mutex};
500-
/// use example_interfaces::srv::*;
501510
///
502511
/// let counter = Arc::new(Mutex::new(0usize));
503512
///
504513
/// let counter_in_service = Arc::clone(&counter);
505-
/// let service = node.create_service::<Trigger, _>(
514+
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
506515
/// "trigger_counter",
507-
/// move |_request: Trigger_Request| {
516+
/// move |_request: example_interfaces::srv::Trigger_Request| {
508517
/// let mut counter = counter_in_service.lock().unwrap();
509518
/// *counter += 1;
510519
/// println!("Triggered {} times", *counter);
511-
/// Trigger_Response {
520+
/// example_interfaces::srv::Trigger_Response {
512521
/// success: true,
513522
/// message: "no problems here".to_string(),
514523
/// }
@@ -588,17 +597,17 @@ impl NodeState {
588597
///
589598
/// ```
590599
/// # use rclrs::*;
600+
/// # use crate::rclrs::vendor::example_interfaces;
591601
/// # let executor = Context::default().create_basic_executor();
592602
/// # let node = executor.create_node("my_node")?;
593603
/// use std::sync::Arc;
594-
/// use example_interfaces::srv::*;
595604
///
596605
/// let worker_a = node.create_worker(0_i64);
597606
/// let worker_b = node.create_worker(0_i64);
598607
///
599-
/// let service = node.create_async_service::<AddTwoInts, _>(
608+
/// let service = node.create_async_service::<example_interfaces::srv::AddTwoInts, _>(
600609
/// "add",
601-
/// move |request: AddTwoInts_Request| {
610+
/// move |request: example_interfaces::srv::AddTwoInts_Request| {
602611
/// // Clone the workers so they can be captured into the async block
603612
/// let worker_a = Arc::clone(&worker_a);
604613
/// let worker_b = Arc::clone(&worker_b);
@@ -617,7 +626,7 @@ impl NodeState {
617626
/// // Awaiting above ensures that each number from the
618627
/// // request is saved in its respective worker before
619628
/// // we give back a response.
620-
/// AddTwoInts_Response { sum: a + b }
629+
/// example_interfaces::srv::AddTwoInts_Response { sum: a + b }
621630
/// }
622631
/// }
623632
/// )?;
@@ -660,6 +669,7 @@ impl NodeState {
660669
/// Pass in only the topic name for the `options` argument to use all default subscription options:
661670
/// ```
662671
/// # use rclrs::*;
672+
/// # use crate::rclrs::vendor::test_msgs;
663673
/// # let executor = Context::default().create_basic_executor();
664674
/// # let node = executor.create_node("my_node").unwrap();
665675
/// let subscription = node.create_subscription(
@@ -675,6 +685,7 @@ impl NodeState {
675685
///
676686
/// ```
677687
/// # use rclrs::*;
688+
/// # use crate::rclrs::vendor::test_msgs;
678689
/// # let executor = Context::default().create_basic_executor();
679690
/// # let node = executor.create_node("my_node").unwrap();
680691
/// let subscription = node.create_subscription(
@@ -717,6 +728,7 @@ impl NodeState {
717728
///
718729
/// ```
719730
/// # use rclrs::*;
731+
/// # use crate::rclrs::vendor::example_interfaces;
720732
/// # let executor = Context::default().create_basic_executor();
721733
/// # let node = executor.create_node("my_node").unwrap();
722734
/// use std::sync::Mutex;
@@ -739,6 +751,7 @@ impl NodeState {
739751
///
740752
/// ```
741753
/// # use rclrs::*;
754+
/// # use crate::rclrs::vendor::example_interfaces;
742755
/// # let executor = Context::default().create_basic_executor();
743756
/// # let node = executor.create_node("my_node").unwrap();
744757
/// use std::sync::{Arc, Mutex};
@@ -839,8 +852,10 @@ impl NodeState {
839852
///
840853
/// ```
841854
/// # use rclrs::*;
855+
/// # use crate::rclrs::vendor::example_interfaces;
842856
/// # let executor = Context::default().create_basic_executor();
843857
/// # let node = executor.create_node("my_node").unwrap();
858+
///
844859
/// use std::sync::Arc;
845860
///
846861
/// let count_worker = node.create_worker(0_usize);
@@ -1094,7 +1109,7 @@ mod tests {
10941109

10951110
#[test]
10961111
fn test_topic_names_and_types() -> Result<(), RclrsError> {
1097-
use test_msgs::msg;
1112+
use crate::vendor::test_msgs::msg;
10981113

10991114
let graph = construct_test_graph("test_topics_graph")?;
11001115

rclrs/src/publisher.rs

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -337,14 +337,15 @@ mod tests {
337337

338338
#[test]
339339
fn traits() {
340+
use crate::vendor::test_msgs;
340341
assert_send::<Publisher<test_msgs::msg::BoundedSequences>>();
341342
assert_sync::<Publisher<test_msgs::msg::BoundedSequences>>();
342343
}
343344

344345
#[test]
345346
fn test_publishers() -> Result<(), RclrsError> {
347+
use crate::vendor::test_msgs::msg;
346348
use crate::TopicEndpointInfo;
347-
use test_msgs::msg;
348349

349350
let namespace = "/test_publishers_graph";
350351
let graph = construct_test_graph(namespace)?;

rclrs/src/publisher/loaned_message.rs

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -99,6 +99,7 @@ mod tests {
9999
#[test]
100100
fn traits() {
101101
use crate::test_helpers::*;
102+
use crate::vendor::test_msgs;
102103

103104
assert_send::<LoanedMessage<test_msgs::msg::rmw::BoundedSequences>>();
104105
assert_sync::<LoanedMessage<test_msgs::msg::rmw::BoundedSequences>>();

rclrs/src/service.rs

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -393,14 +393,15 @@ mod tests {
393393

394394
#[test]
395395
fn traits() {
396+
use crate::vendor::test_msgs;
396397
assert_send::<Service<test_msgs::srv::Arrays>>();
397398
assert_sync::<Service<test_msgs::srv::Arrays>>();
398399
}
399400

400401
#[test]
401402
fn test_services() -> Result<(), RclrsError> {
403+
use crate::vendor::test_msgs::srv;
402404
use crate::TopicNamesAndTypes;
403-
use test_msgs::srv;
404405

405406
let namespace = "/test_services_graph";
406407
let graph = construct_test_graph(namespace)?;

0 commit comments

Comments
 (0)