Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions rclrs/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,6 @@ serde-big-array = { version = "0.5.1", optional = true }
[dev-dependencies]
# Needed for e.g. writing yaml files in tests
tempfile = "3.3.0"
# Needed for publisher and subscriber tests
test_msgs = {version = "*"}
# Used in doctests
example_interfaces = { version = "*" }
# Needed for parameter service tests
tokio = { version = "1", features = ["rt", "time", "macros"] }

Expand Down
32 changes: 16 additions & 16 deletions rclrs/src/client.rs
Original file line number Diff line number Diff line change
Expand Up @@ -159,17 +159,17 @@ where
/// signatures and which returns a `()` (a.k.a. nothing).
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm a bit confused about the leading crate:: here since I thought doctests give a compilation error when you do use crate::. But I guess if the tests are passing then 🤷

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think we even need crate::. Locally, doctests seem to be passing with out it

/// # let node = Context::default()
/// # .create_basic_executor()
/// # .create_node("test_node")?;
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
///
/// async fn print_hello(_response: Empty_Response) {
/// async fn print_hello(_response: test_msgs::srv::Empty_Response) {
/// print!("Hello!");
/// }
///
/// let client = node.create_client::<Empty>("my_service")?;
/// let request = Empty_Request::default();
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
/// let request = test_msgs::srv::Empty_Request::default();
/// let promise = client.call_then_async(&request, print_hello)?;
/// # Ok::<(), RclrsError>(())
/// ```
Expand All @@ -187,21 +187,21 @@ where
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # use std::future::Future;
/// # let node = Context::default()
/// # .create_basic_executor()
/// # .create_node("test_node")?;
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
///
/// fn print_greeting(_response: Empty_Response) -> impl Future<Output=()> {
/// fn print_greeting(_response: test_msgs::srv::Empty_Response) -> impl Future<Output=()> {
/// let greeting = "Hello!";
/// async move {
/// print!("Hello!");
/// }
/// }
///
/// let client = node.create_client::<Empty>("my_service")?;
/// let request = Empty_Request::default();
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
/// let request = test_msgs::srv::Empty_Request::default();
/// let promise = client.call_then_async(
/// &request,
/// print_greeting)?;
Expand All @@ -216,17 +216,17 @@ where
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let node = Context::default()
/// # .create_basic_executor()
/// # .create_node("test_node")?;
/// use test_msgs::srv::{Empty, Empty_Request, Empty_Response};
///
/// let greeting = "Hello!";
/// let client = node.create_client::<Empty>("my_service")?;
/// let request = Empty_Request::default();
/// let client = node.create_client::<test_msgs::srv::Empty>("my_service")?;
/// let request = test_msgs::srv::Empty_Request::default();
/// let promise = client.call_then_async(
/// &request,
/// move |response: Empty_Response| {
/// move |response: test_msgs::srv::Empty_Response| {
/// async move {
/// print!("{greeting}");
/// }
Expand Down Expand Up @@ -568,12 +568,12 @@ unsafe impl Send for rcl_client_t {}
mod tests {
use super::*;
use crate::test_helpers::*;
use test_msgs::srv;
use crate::vendor::test_msgs;

#[test]
fn traits() {
assert_send::<Client<srv::Arrays>>();
assert_sync::<Client<srv::Arrays>>();
assert_send::<Client<test_msgs::srv::Arrays>>();
assert_sync::<Client<test_msgs::srv::Arrays>>();
}

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

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

Expand Down
6 changes: 5 additions & 1 deletion rclrs/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
//!
//! ```no_run
//! use rclrs::*;
//! # use crate::rclrs::vendor::example_interfaces;
//!
//! let context = Context::default_from_env()?;
//! let mut executor = context.create_basic_executor();
Expand All @@ -58,6 +59,7 @@
//! # let context = Context::default_from_env()?;
//! # let mut executor = context.create_basic_executor();
//! # let node = executor.create_node("example_node")?;
//! # use crate::rclrs::vendor::example_interfaces;
//! #
//! // This worker will manage the data for us.
//! // The worker's data is called its payload.
Expand Down Expand Up @@ -97,6 +99,7 @@
//! The following is a simple example of using a mandatory parameter:
//! ```no_run
//! use rclrs::*;
//! # use crate::rclrs::vendor::example_interfaces;
//! use std::sync::Arc;
//!
//! let mut executor = Context::default_from_env()?.create_basic_executor();
Expand Down Expand Up @@ -126,6 +129,7 @@
//!
//! ```no_run
//! use rclrs::*;
//! # use crate::rclrs::vendor::example_interfaces;
//! use std::time::Duration;
//!
//! let mut executor = Context::default_from_env()?.create_basic_executor();
Expand Down Expand Up @@ -189,7 +193,7 @@ mod service;
mod subscription;
mod time;
mod time_source;
mod vendor;
pub mod vendor;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Oh this needs to be pub because doctest only links to public stuff... Jeez, I can see this causing some confusion. I think we need to re-evaluate our message consumption more and more everyday 😅

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, and I had to modify the vendorize script to not complain about missing docs for messages because now they are public 😅

mod wait_set;
mod worker;

Expand Down
41 changes: 28 additions & 13 deletions rclrs/src/node.rs
Original file line number Diff line number Diff line change
Expand Up @@ -244,6 +244,7 @@ impl NodeState {
/// In some cases the payload type can be inferred by Rust:
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// let executor = Context::default().create_basic_executor();
/// let node = executor.create_node("my_node").unwrap();
///
Expand All @@ -269,6 +270,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let worker = node.create_worker::<String>(String::new());
Expand All @@ -277,6 +279,7 @@ impl NodeState {
/// The data given to the worker can be any custom data type:
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
///
Expand Down Expand Up @@ -312,6 +315,7 @@ impl NodeState {
/// # use rclrs::*;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// # use crate::rclrs::vendor::test_msgs;
/// let client = node.create_client::<test_msgs::srv::Empty>(
/// "my_service"
/// )
Expand All @@ -325,6 +329,7 @@ impl NodeState {
/// # use rclrs::*;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// # use crate::rclrs::vendor::test_msgs;
/// let client = node.create_client::<test_msgs::srv::Empty>(
/// "my_service"
/// .keep_all()
Expand Down Expand Up @@ -357,6 +362,7 @@ impl NodeState {
/// # use rclrs::*;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// # use crate::rclrs::vendor::test_msgs;
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
/// "my_topic"
/// )
Expand All @@ -368,6 +374,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let publisher = node.create_publisher::<test_msgs::msg::Empty>(
Expand Down Expand Up @@ -414,6 +421,7 @@ impl NodeState {
/// Pass in only the service name for the `options` argument to use all default service options:
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
Expand All @@ -430,6 +438,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let service = node.create_service::<test_msgs::srv::Empty, _>(
Expand Down Expand Up @@ -468,19 +477,19 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// use std::sync::Mutex;
/// use example_interfaces::srv::*;
///
/// let counter = Mutex::new(0usize);
/// let service = node.create_service::<Trigger, _>(
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
/// "trigger_counter",
/// move |_request: Trigger_Request| {
/// move |_request: example_interfaces::srv::Trigger_Request| {
/// let mut counter = counter.lock().unwrap();
/// *counter += 1;
/// println!("Triggered {} times", *counter);
/// Trigger_Response {
/// example_interfaces::srv::Trigger_Response {
/// success: true,
/// message: "no problems here".to_string(),
/// }
Expand All @@ -494,21 +503,21 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// use std::sync::{Arc, Mutex};
/// use example_interfaces::srv::*;
///
/// let counter = Arc::new(Mutex::new(0usize));
///
/// let counter_in_service = Arc::clone(&counter);
/// let service = node.create_service::<Trigger, _>(
/// let service = node.create_service::<example_interfaces::srv::Trigger, _>(
/// "trigger_counter",
/// move |_request: Trigger_Request| {
/// move |_request: example_interfaces::srv::Trigger_Request| {
/// let mut counter = counter_in_service.lock().unwrap();
/// *counter += 1;
/// println!("Triggered {} times", *counter);
/// Trigger_Response {
/// example_interfaces::srv::Trigger_Response {
/// success: true,
/// message: "no problems here".to_string(),
/// }
Expand Down Expand Up @@ -588,17 +597,17 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node")?;
/// use std::sync::Arc;
/// use example_interfaces::srv::*;
///
/// let worker_a = node.create_worker(0_i64);
/// let worker_b = node.create_worker(0_i64);
///
/// let service = node.create_async_service::<AddTwoInts, _>(
/// let service = node.create_async_service::<example_interfaces::srv::AddTwoInts, _>(
/// "add",
/// move |request: AddTwoInts_Request| {
/// move |request: example_interfaces::srv::AddTwoInts_Request| {
/// // Clone the workers so they can be captured into the async block
/// let worker_a = Arc::clone(&worker_a);
/// let worker_b = Arc::clone(&worker_b);
Expand All @@ -617,7 +626,7 @@ impl NodeState {
/// // Awaiting above ensures that each number from the
/// // request is saved in its respective worker before
/// // we give back a response.
/// AddTwoInts_Response { sum: a + b }
/// example_interfaces::srv::AddTwoInts_Response { sum: a + b }
/// }
/// }
/// )?;
Expand Down Expand Up @@ -660,6 +669,7 @@ impl NodeState {
/// Pass in only the topic name for the `options` argument to use all default subscription options:
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let subscription = node.create_subscription(
Expand All @@ -675,6 +685,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::test_msgs;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// let subscription = node.create_subscription(
Expand Down Expand Up @@ -717,6 +728,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// use std::sync::Mutex;
Expand All @@ -739,6 +751,7 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
/// use std::sync::{Arc, Mutex};
Expand Down Expand Up @@ -839,8 +852,10 @@ impl NodeState {
///
/// ```
/// # use rclrs::*;
/// # use crate::rclrs::vendor::example_interfaces;
/// # let executor = Context::default().create_basic_executor();
/// # let node = executor.create_node("my_node").unwrap();
///
/// use std::sync::Arc;
///
/// let count_worker = node.create_worker(0_usize);
Expand Down Expand Up @@ -1094,7 +1109,7 @@ mod tests {

#[test]
fn test_topic_names_and_types() -> Result<(), RclrsError> {
use test_msgs::msg;
use crate::vendor::test_msgs::msg;

let graph = construct_test_graph("test_topics_graph")?;

Expand Down
3 changes: 2 additions & 1 deletion rclrs/src/publisher.rs
Original file line number Diff line number Diff line change
Expand Up @@ -337,14 +337,15 @@ mod tests {

#[test]
fn traits() {
use crate::vendor::test_msgs;
assert_send::<Publisher<test_msgs::msg::BoundedSequences>>();
assert_sync::<Publisher<test_msgs::msg::BoundedSequences>>();
}

#[test]
fn test_publishers() -> Result<(), RclrsError> {
use crate::vendor::test_msgs::msg;
use crate::TopicEndpointInfo;
use test_msgs::msg;

let namespace = "/test_publishers_graph";
let graph = construct_test_graph(namespace)?;
Expand Down
1 change: 1 addition & 0 deletions rclrs/src/publisher/loaned_message.rs
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ mod tests {
#[test]
fn traits() {
use crate::test_helpers::*;
use crate::vendor::test_msgs;

assert_send::<LoanedMessage<test_msgs::msg::rmw::BoundedSequences>>();
assert_sync::<LoanedMessage<test_msgs::msg::rmw::BoundedSequences>>();
Expand Down
3 changes: 2 additions & 1 deletion rclrs/src/service.rs
Original file line number Diff line number Diff line change
Expand Up @@ -393,14 +393,15 @@ mod tests {

#[test]
fn traits() {
use crate::vendor::test_msgs;
assert_send::<Service<test_msgs::srv::Arrays>>();
assert_sync::<Service<test_msgs::srv::Arrays>>();
}

#[test]
fn test_services() -> Result<(), RclrsError> {
use crate::vendor::test_msgs::srv;
use crate::TopicNamesAndTypes;
use test_msgs::srv;

let namespace = "/test_services_graph";
let graph = construct_test_graph(namespace)?;
Expand Down
Loading
Loading