From 92edc211383022534eb4efb4fa2d45c543111d96 Mon Sep 17 00:00:00 2001 From: roboticswithjulia Date: Wed, 26 Mar 2025 00:35:35 +0100 Subject: [PATCH 1/9] Add first_rclrs_node example and update documentation links --- README.md | 2 +- docs/writing-your-first-rclrs-node.md | 226 -------------- examples/minimal_pub_sub/Cargo.toml | 5 + .../minimal_pub_sub/src/first_rclrs_node.rs | 289 ++++++++++++++++++ 4 files changed, 295 insertions(+), 227 deletions(-) delete mode 100644 docs/writing-your-first-rclrs-node.md create mode 100644 examples/minimal_pub_sub/src/first_rclrs_node.rs diff --git a/README.md b/README.md index e05317fb8..d9e0efcf1 100644 --- a/README.md +++ b/README.md @@ -71,5 +71,5 @@ ros2 launch examples_rclrs_minimal_pub_sub minimal_pub_sub.launch.xml ``` Further documentation articles: -- [Tutorial on writing your first node with `rclrs`](docs/writing-your-first-rclrs-node.md) +- [Tutorial on writing your first node with `rclrs`](./examples/minimal_pub_sub/src/first_rclrs_node.rs) - [Contributor's guide](docs/CONTRIBUTING.md) diff --git a/docs/writing-your-first-rclrs-node.md b/docs/writing-your-first-rclrs-node.md deleted file mode 100644 index 8dbd8d2fa..000000000 --- a/docs/writing-your-first-rclrs-node.md +++ /dev/null @@ -1,226 +0,0 @@ -# Writing your first `rclrs` node - -This tutorial is intended to point out some of the differences of the Rust client library with the other client libraries. It assumes knowledge of Rust, and is also not intended to be an introduction to ROS 2. - -As a semi-realistic example, let's create a node that periodically republishes the last message it received. It's limited to only one specific message type – `std_msgs/msg/String` in this example. - -## Create a package - -In ROS 2, `ros2 pkg create` is the standard way of creating packages. However, the functionality to create Rust packages with this tool is not yet implemented, so they need to be created manually. - -You can start by creating a package with `cargo` in the usual way: - -```console -cargo new republisher_node && cd republisher_node -``` - -In the `Cargo.toml` file, add a dependency on `rclrs = "*"` and `std_msgs = "*"`. - -Additionally, create a new `package.xml` if you want your node to be buildable with `colcon`. Make sure to change the build type to `ament_cargo` and to include the two packages mentioned above in the dependencies, as such: - -```xml - - republisher_node - 0.0.0 - TODO: Package description - user - TODO: License declaration - - rclrs - std_msgs - - - ament_cargo - - -``` - - -## Writing the basic node structure - -Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`. - -Instead, you can store the node as a regular member. Let's add a struct that contains the node, a subscription, and a field for the last message that was received to `main.rs`: - -```rust -use std::sync::Arc; -use std_msgs::msg::String as StringMsg; - -struct RepublisherNode { - node: Arc, - _subscription: Arc>, - data: Option, -} - -impl RepublisherNode { - fn new(context: &rclrs::Context) -> Result { - let node = rclrs::Node::new(context, "republisher")?; - let data = None; - let _subscription = node.create_subscription( - "in_topic", - rclrs::QOS_PROFILE_DEFAULT, - |msg: StringMsg| { todo!("Assign msg to self.data") }, - )?; - Ok(Self { - node, - _subscription, - data, - }) - } -} -``` - -Next, add a main function to launch it: - -```rust -fn main() -> Result<(), rclrs::RclrsError> { - let context = rclrs::Context::new(std::env::args())?; - let republisher = RepublisherNode::new(&context)?; - rclrs::spin(republisher.node) -} -``` - -You should now be able to run this node with `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. - - -## Storing received data in the struct - -Let's do something about that `todo!`. The obvious thing for the subscription callback to do would be this: - -```rust -|msg: StringMsg| { - data = Some(msg); -}, -``` - -This is a standard pattern in C++, but doesn't work in Rust. Why not? - -Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely. - -> 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. - -You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. That variable lives considerably longer, but also not forever, so it wouldn't be enough. A secondary problem is that it would be a *self-referential struct*, which is not allowed in Rust. - -The solution is _shared ownership_ of the data by the callback and the node. The `Arc` type provides shared ownership, but since it only gives out shared references to its data, we also need a `Mutex` or a `RefCell`. This `Arc>` type is a frequent pattern in Rust code. - -So, to store the received data in the struct, the following things have to change: -1. Import `Mutex` -2. Adjust the type of the `data` field -3. Create two pointers to the same data (wrapped in a `Mutex`) -4. Make the closure `move`, and inside it, lock the `Mutex` and store the message - -```rust -use std::sync::{Arc, Mutex}; // (1) -use std_msgs::msg::String as StringMsg; - -struct RepublisherNode { - node: Arc, - _subscription: Arc>, - data: Arc>>, // (2) -} - -impl RepublisherNode { - fn new(context: &rclrs::Context) -> Result { - let node = rclrs::Node::new(context, "republisher")?; - let data = Arc::new(Mutex::new(None)); // (3) - let data_cb = Arc::clone(&data); - let _subscription = { - // Create a new shared pointer instance that will be owned by the closure - node.create_subscription( - "in_topic", - rclrs::QOS_PROFILE_DEFAULT, - move |msg: StringMsg| { - // This subscription now owns the data_cb variable - *data_cb.lock().unwrap() = Some(msg); // (4) - }, - )? - }; - Ok(Self { - node, - _subscription, - data, - }) - } -} -``` - -If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed. - -If you couldn't follow the explanation involving borrowing, closures etc. above, an explanation of these concepts is unfortunately out of scope of this tutorial. There are many good Rust books and tutorials that can help you understand these crucial features. The online book [*The Rust Programming Language*](https://doc.rust-lang.org/book/) is a good place to start for most topics. - -## Periodically run a republishing function - -The node still doesn't republish the received messages. First, let's add a publisher to the node: - -```rust -// Add this new field to the RepublisherNode struct, after the subscription: -publisher: Arc>, - -// Change the end of RepublisherNode::new() to this: -let publisher = node.create_publisher("out_topic", rclrs::QOS_PROFILE_DEFAULT)?; -Ok(Self { - node, - _subscription, - publisher, - data, -}) -``` - -Then, let's add a `republish()` function to the `RepublisherNode` that publishes the latest message received, or does nothing if none was received: - -```rust -fn republish(&self) -> Result<(), rclrs::RclrsError> { - if let Some(s) = &*self.data.lock().unwrap() { - self.publisher.publish(s)?; - } - Ok(()) -} -``` - -What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread: - -```rust -fn main() -> Result<(), rclrs::RclrsError> { - let context = rclrs::Context::new(std::env::args())?; - let republisher = RepublisherNode::new(&context)?; - std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { - loop { - use std::time::Duration; - std::thread::sleep(Duration::from_millis(1000)); - republisher.republish()?; - } - }); - rclrs::spin(republisher.node) -} -``` - -But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, because the function that the variable is coming from might return before the thread that borrows the variable ends. - -> 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. - -The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` and the `republish()` function only require a shared reference: - -```rust -fn main() -> Result<(), rclrs::RclrsError> { - let context = rclrs::Context::new(std::env::args())?; - let republisher = Arc::new(RepublisherNode::new(&context)?); - let republisher_other_thread = Arc::clone(&republisher); - std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { - loop { - use std::time::Duration; - std::thread::sleep(Duration::from_millis(1000)); - republisher_other_thread.republish()?; - } - }); - rclrs::spin(Arc::clone(&republisher.node)) -} -``` - - -## Trying it out - -In separate terminals, run `cargo run` and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. - -In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. - -Now publish another message, e.g. `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Servus"}' -1` and observe the `ros2 topic echo` terminal receiving that message from that point forward. diff --git a/examples/minimal_pub_sub/Cargo.toml b/examples/minimal_pub_sub/Cargo.toml index 52c4f0544..4092c8840 100644 --- a/examples/minimal_pub_sub/Cargo.toml +++ b/examples/minimal_pub_sub/Cargo.toml @@ -25,6 +25,11 @@ path = "src/zero_copy_subscriber.rs" name = "zero_copy_publisher" path = "src/zero_copy_publisher.rs" +[[bin]] +name = "first_rclrs_node" +path = "src/first_rclrs_node.rs" + + [dependencies] anyhow = {version = "1", features = ["backtrace"]} diff --git a/examples/minimal_pub_sub/src/first_rclrs_node.rs b/examples/minimal_pub_sub/src/first_rclrs_node.rs new file mode 100644 index 000000000..a8d5740b8 --- /dev/null +++ b/examples/minimal_pub_sub/src/first_rclrs_node.rs @@ -0,0 +1,289 @@ +//! # First rclrs node +//! This tutorial is intended to point out some of the differences of the Rust client library with the other client libraries. It assumes knowledge of Rust, and is also not intended to be an introduction to ROS 2. +//! +//! As a semi-realistic example, let's create a node that periodically republishes the last message it received. It's limited to only one specific message type – `std_msgs/msg/String` in this example. +//! +//! ## Create a package +//! In ROS 2, `ros2 pkg create` is the standard way of creating packages. However, the functionality to create Rust packages with this tool is not yet implemented, so they need to be created manually. +//! +//! You can use the current package that has already been created, or you can create a new package using `cargo` as usual: +//! ```console +//! cargo new republisher_node && cd republisher_node +//! ``` + +//! In the `Cargo.toml` file, add dependencies for `rclrs = "*"` and `std_msgs = "*"`, if they are not already included. +//! +//! Additionally, a new `package.xml` needs to be created if you want your node to be buildable with `colcon` and make sure to change the build type to `ament_cargo` and to include the two packages mentioned above in the dependencies, as such: +//!```xml +//! +//! republisher_node +//! 0.0.0 +//! TODO: Package description +//! user +//! TODO: License declaration +//! +//! rclrs +//! std_msgs +//! +//! +//! ament_cargo +//! +//! +//! ``` + +//! ## Write the basic node structure +//! Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`. +//! +//! Instead, you can store the node as a regular member. Let's use a struct that contains the node, a subscription, and a field for the last message that was received to `main.rs`: + +//! ```rust +//! use std::sync::Arc; +//! use std_msgs::msg::String as StringMsg; +//! use rclrs::*; + +//! struct RepublisherNode { +//! _node: Arc, +//! _subscription: Arc>, +//! _data: Option, +//!} + +//! impl RepublisherNode { +//! fn new(executor: &rclrs::Executor) -> Result { +//! +//! let _node = executor.create_node("republisher")?; +//! let _data = None; +//! let _subscription = _node.create_subscription( +//! "in_topic", +//! |_msg: StringMsg| { todo!("Assign msg to self.data") }, +//! )?; +//! Ok(Self { +//! _node, +//! _subscription, +//! _data, +//! }) +//! } +//!} +//! ``` + +//! Next, add a main function to launch it: + +//!```rust +//! fn main() -> Result<(), rclrs::RclrsError> { +//! let context = Context::default_from_env()?; +//! let mut executor = context.create_basic_executor(); +//! let _republisher = RepublisherNode::new(&executor)?; +//! executor +//! .spin(SpinOptions::default()) +//! .first_error() +//! .map_err(|err| err.into()) +//!} +//! ``` + + +//! ## Run the node +//! You should now be able to run this node with `cargo build` and then `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. + +//! ## Storing received data in the struct +//! Let's do something about that `todo!`. The obvious thing for the subscription callback to do would be this: + +//! ```rust +//! |msg: StringMsg| { +//! data = Some(msg); +//!}, +//!``` + + +//! This is a standard pattern in C++, but doesn't work in Rust. Why not? +//! +//! Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. +//! The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely. +//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. +//! +//! You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. +//! That variable lives considerably longer, but also not forever, so it wouldn't be enough. A secondary problem is that it would be a *self-referential struct*, which is not allowed in Rust. +//! +//! The solution is _shared ownership_ of the data by the callback and the node. The `Arc` type provides shared ownership, but since it only gives out shared references to its data, +//! we also need a `Mutex` or a `RefCell`. This `Arc>` type is a frequent pattern in Rust code. +//! +//! So, to store the received data in the struct, the following things have to change: +//! 1. Import `Mutex` +//! 2. Adjust the type of the `data` field +//! 3. Create two pointers to the same data (wrapped in a `Mutex`) +//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message + +//! ```rust +//! use std::sync::{Arc, Mutex}; // (1) +//! use std_msgs::msg::String as StringMsg; +//! use rclrs::*; + +//! struct RepublisherNode { +//! _node: Arc, +//! _subscription: Arc>, +//! _data: Arc>>, // (2) +//! } + +//! impl RepublisherNode { +//! fn new(executor: &rclrs::Executor) -> Result { +//! let _node = executor.create_node("republisher")?; +//! let _data = Arc::new(Mutex::new(None)); // (3) +//! let data_cb = Arc::clone(&_data); +//! let _subscription = _node.create_subscription( +//! "in_topic".keep_last(10).transient_local(), // (4) +//! move |msg: StringMsg| { +//! *data_cb.lock().unwrap() = Some(msg); +//! }, +//! )?; +//! Ok(Self { +//! _node, +//! _subscription, +//! _data, +//! }) +//! } +//! } + +//! ``` +//! + +//! If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed. +//! +//! If you couldn't follow the explanation involving borrowing, closures etc. above, an explanation of these concepts is unfortunately out of scope of this tutorial. +//! There are many good Rust books and tutorials that can help you understand these crucial features. The online book [*The Rust Programming Language*](https://doc.rust-lang.org/book/) is a good place to start for most topics. + + +//! ## Periodically run a republishing function +//! +//! The node still doesn't republish the received messages. First, let's add a publisher to the node: + +//! ```rust +//! // Add this new field to the RepublisherNode struct, after the subscription: +//! _publisher: Arc>, +//! +//! // Change the end of RepublisherNode::new() to this: +//! let _publisher = _node.create_publisher::("out_topic")?; +//! Ok(Self { +//! _node, +//! _subscription, +//! _publisher, +//! _data, +//! }) +//! ``` + +//! Then, let's add a `republish()` function to the `RepublisherNode` struct that periodically republishes the last message received, or does nothing if none was received: +//! +//! ```rust +//!fn republish(&self) -> Result<(), rclrs::RclrsError> { +//! if let Some(s) = &*self._data.lock().unwrap() { +//! self._publisher.publish(s)?; +//! } +//! Ok(()) +//! } +//! ``` + +//! What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, +//! but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread: +//! +//! ```rust +//! fn main() -> Result<(), rclrs::RclrsError> { +//! let context = Context::default_from_env()?; +//! let mut executor = context.create_basic_executor(); +//! let _republisher = RepublisherNode::new(&executor)?; +//! std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { +//! loop { +//! use std::time::Duration; +//! std::thread::sleep(Duration::from_millis(1000)); +//! _republisher.republish()?; +//! } +//! }); +//! executor +//! .spin(SpinOptions::default()) +//! .first_error() +//! .map_err(|err| err.into()) +//!} +//!``` + + +//! But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. +//! That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, +//! because the function that the variable is coming from might return before the thread that borrows the variable ends. +//! > 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. +//! +//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` +//! and the `republish()` function only require a shared reference: +//! ```rust +//! fn main() -> Result<(), rclrs::RclrsError> { +//! let context = Context::default_from_env()?; +//! let mut executor = context.create_basic_executor(); +//! let _republisher = RepublisherNode::new(&executor)?; +//! std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { +//! loop { +//! use std::time::Duration; +//! std::thread::sleep(Duration::from_millis(1000)); +//! _republisher.republish()?; +//! } +//! }); +//! executor +//! .spin(SpinOptions::default()) +//! .first_error() +//! .map_err(|err| err.into()) +//!} +//!``` + +//! ## Try it out +//! In separate terminals, run `cargo run --bin first_rclrs_node` if running the current node or `cargo run` otherwise and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. +//! +//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. +//! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. +//! +//! Now publish another message, e.g. `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Servus"}' -1` and observe the `ros2 topic echo` terminal receiving that message from that point forward. + +use std::sync::{Arc, Mutex}; // (1) +use std_msgs::msg::String as StringMsg; +use rclrs::*; +struct RepublisherNode { + _node: Arc, + _subscription: Arc>, + _publisher: Arc>, + _data: Arc>>, // (2) +} +impl RepublisherNode { + fn new(executor: &rclrs::Executor) -> Result { + let _node = executor.create_node("republisher")?; + let _data = Arc::new(Mutex::new(None)); // (3) + let data_cb = Arc::clone(&_data); + let _subscription = _node.create_subscription( + "in_topic".keep_last(10).transient_local(), // (4) + move |msg: StringMsg| { + *data_cb.lock().unwrap() = Some(msg); + }, + )?; + let _publisher = _node.create_publisher::("out_topic")?; + Ok(Self { + _node, + _subscription, + _publisher, + _data, + }) + } + fn republish(&self) -> Result<(), rclrs::RclrsError> { + if let Some(s) = &*self._data.lock().unwrap() { + self._publisher.publish(s)?; + } + Ok(()) + } +} +fn main() -> Result<(), rclrs::RclrsError> { + let context = Context::default_from_env()?; + let mut executor = context.create_basic_executor(); + let _republisher = RepublisherNode::new(&executor)?; + std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { + loop { + use std::time::Duration; + std::thread::sleep(Duration::from_millis(1000)); + _republisher.republish()?; + } + }); + executor + .spin(SpinOptions::default()) + .first_error() + .map_err(|err| err.into()) + } \ No newline at end of file From 942e3101fc9402b6ea83ad1e9887faac881ae7e7 Mon Sep 17 00:00:00 2001 From: roboticswithjulia Date: Wed, 26 Mar 2025 15:34:10 +0100 Subject: [PATCH 2/9] Refactor first_rclrs_node example for improved clarity and structure --- .../minimal_pub_sub/src/first_rclrs_node.rs | 162 ++++++++---------- 1 file changed, 76 insertions(+), 86 deletions(-) diff --git a/examples/minimal_pub_sub/src/first_rclrs_node.rs b/examples/minimal_pub_sub/src/first_rclrs_node.rs index a8d5740b8..be7e28482 100644 --- a/examples/minimal_pub_sub/src/first_rclrs_node.rs +++ b/examples/minimal_pub_sub/src/first_rclrs_node.rs @@ -5,12 +5,11 @@ //! //! ## Create a package //! In ROS 2, `ros2 pkg create` is the standard way of creating packages. However, the functionality to create Rust packages with this tool is not yet implemented, so they need to be created manually. -//! +//! //! You can use the current package that has already been created, or you can create a new package using `cargo` as usual: //! ```console //! cargo new republisher_node && cd republisher_node //! ``` - //! In the `Cargo.toml` file, add dependencies for `rclrs = "*"` and `std_msgs = "*"`, if they are not already included. //! //! Additionally, a new `package.xml` needs to be created if you want your node to be buildable with `colcon` and make sure to change the build type to `ament_cargo` and to include the two packages mentioned above in the dependencies, as such: @@ -62,23 +61,19 @@ //! _data, //! }) //! } -//!} -//! ``` - +//!}``` //! Next, add a main function to launch it: -//!```rust +//! ```rust //! fn main() -> Result<(), rclrs::RclrsError> { -//! let context = Context::default_from_env()?; -//! let mut executor = context.create_basic_executor(); -//! let _republisher = RepublisherNode::new(&executor)?; -//! executor -//! .spin(SpinOptions::default()) -//! .first_error() -//! .map_err(|err| err.into()) -//!} -//! ``` - +//! let context = Context::default_from_env()?; +//! let mut executor = context.create_basic_executor(); +//! let _republisher = RepublisherNode::new(&executor)?; +//! executor +//! .spin(SpinOptions::default()) +//! .first_error() +//! .map_err(|err| err.into()) +//! }``` //! ## Run the node //! You should now be able to run this node with `cargo build` and then `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. @@ -89,17 +84,15 @@ //! ```rust //! |msg: StringMsg| { //! data = Some(msg); -//!}, -//!``` - - +//! } +//! ``` //! This is a standard pattern in C++, but doesn't work in Rust. Why not? //! -//! Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. +//! Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. //! The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely. -//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. +//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. //! -//! You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. +//! You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. //! That variable lives considerably longer, but also not forever, so it wouldn't be enough. A secondary problem is that it would be a *self-referential struct*, which is not allowed in Rust. //! //! The solution is _shared ownership_ of the data by the callback and the node. The `Arc` type provides shared ownership, but since it only gives out shared references to its data, @@ -109,7 +102,7 @@ //! 1. Import `Mutex` //! 2. Adjust the type of the `data` field //! 3. Create two pointers to the same data (wrapped in a `Mutex`) -//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message +//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message //! ```rust //! use std::sync::{Arc, Mutex}; // (1) @@ -140,20 +133,17 @@ //! }) //! } //! } - //! ``` //! - //! If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed. -//! +//! //! If you couldn't follow the explanation involving borrowing, closures etc. above, an explanation of these concepts is unfortunately out of scope of this tutorial. //! There are many good Rust books and tutorials that can help you understand these crucial features. The online book [*The Rust Programming Language*](https://doc.rust-lang.org/book/) is a good place to start for most topics. - - +//! //! ## Periodically run a republishing function -//! +//! //! The node still doesn't republish the received messages. First, let's add a publisher to the node: - +//! //! ```rust //! // Add this new field to the RepublisherNode struct, after the subscription: //! _publisher: Arc>, @@ -167,7 +157,6 @@ //! _data, //! }) //! ``` - //! Then, let's add a `republish()` function to the `RepublisherNode` struct that periodically republishes the last message received, or does nothing if none was received: //! //! ```rust @@ -178,36 +167,34 @@ //! Ok(()) //! } //! ``` - //! What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, //! but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread: //! //! ```rust //! fn main() -> Result<(), rclrs::RclrsError> { -//! let context = Context::default_from_env()?; -//! let mut executor = context.create_basic_executor(); -//! let _republisher = RepublisherNode::new(&executor)?; -//! std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { -//! loop { -//! use std::time::Duration; -//! std::thread::sleep(Duration::from_millis(1000)); -//! _republisher.republish()?; -//! } -//! }); -//! executor -//! .spin(SpinOptions::default()) -//! .first_error() -//! .map_err(|err| err.into()) -//!} -//!``` - - -//! But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. -//! That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, +//! let context = Context::default_from_env()?; +//! let mut executor = context.create_basic_executor(); +//! let _republisher = RepublisherNode::new(&executor)?; +//! std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { +//! loop { +//! use std::time::Duration; +//! std::thread::sleep(Duration::from_millis(1000)); +//! _republisher.republish()?; +//! } +//! }); +//! executor +//! .spin(SpinOptions::default()) +//! .first_error() +//! .map_err(|err| err.into()) +//! } +//! ``` +//! +//! But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. +//! That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, //! because the function that the variable is coming from might return before the thread that borrows the variable ends. //! > 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. -//! -//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` +//! +//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` //! and the `republish()` function only require a shared reference: //! ```rust //! fn main() -> Result<(), rclrs::RclrsError> { @@ -231,43 +218,46 @@ //! ## Try it out //! In separate terminals, run `cargo run --bin first_rclrs_node` if running the current node or `cargo run` otherwise and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. //! -//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. +//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. //! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. //! //! Now publish another message, e.g. `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Servus"}' -1` and observe the `ros2 topic echo` terminal receiving that message from that point forward. -use std::sync::{Arc, Mutex}; // (1) -use std_msgs::msg::String as StringMsg; use rclrs::*; +use std::sync::{Arc, Mutex}; +use std_msgs::msg::String as StringMsg; + struct RepublisherNode { - _node: Arc, - _subscription: Arc>, - _publisher: Arc>, - _data: Arc>>, // (2) + _node: Arc, + _subscription: Arc>, + _publisher: Arc>, + _data: Arc>>, } + impl RepublisherNode { - fn new(executor: &rclrs::Executor) -> Result { - let _node = executor.create_node("republisher")?; - let _data = Arc::new(Mutex::new(None)); // (3) - let data_cb = Arc::clone(&_data); - let _subscription = _node.create_subscription( - "in_topic".keep_last(10).transient_local(), // (4) - move |msg: StringMsg| { - *data_cb.lock().unwrap() = Some(msg); - }, - )?; - let _publisher = _node.create_publisher::("out_topic")?; - Ok(Self { - _node, - _subscription, - _publisher, - _data, - }) - } - fn republish(&self) -> Result<(), rclrs::RclrsError> { + fn new(executor: &rclrs::Executor) -> Result { + let _node = executor.create_node("republisher")?; + let _data = Arc::new(Mutex::new(None)); + let data_cb = Arc::clone(&_data); + let _subscription = _node.create_subscription( + "in_topic".keep_last(10).transient_local(), + move |msg: StringMsg| { + *data_cb.lock().unwrap() = Some(msg); + }, + )?; + let _publisher = _node.create_publisher::("out_topic")?; + Ok(Self { + _node, + _subscription, + _publisher, + _data, + }) + } + + fn republish(&self) -> Result<(), rclrs::RclrsError> { if let Some(s) = &*self._data.lock().unwrap() { self._publisher.publish(s)?; - } + } Ok(()) } } @@ -283,7 +273,7 @@ fn main() -> Result<(), rclrs::RclrsError> { } }); executor - .spin(SpinOptions::default()) - .first_error() - .map_err(|err| err.into()) - } \ No newline at end of file + .spin(SpinOptions::default()) + .first_error() + .map_err(|err| err.into()) +} From 6af482478ea6435ad04b22e6faeaaee97a59ad77 Mon Sep 17 00:00:00 2001 From: roboticswithjulia Date: Wed, 26 Mar 2025 17:14:33 +0100 Subject: [PATCH 3/9] Update first_rclrs_node example for improved clarity and functionality --- .../minimal_pub_sub/src/first_rclrs_node.rs | 21 ++++++++++++------- 1 file changed, 14 insertions(+), 7 deletions(-) diff --git a/examples/minimal_pub_sub/src/first_rclrs_node.rs b/examples/minimal_pub_sub/src/first_rclrs_node.rs index be7e28482..f224fab4b 100644 --- a/examples/minimal_pub_sub/src/first_rclrs_node.rs +++ b/examples/minimal_pub_sub/src/first_rclrs_node.rs @@ -61,7 +61,8 @@ //! _data, //! }) //! } -//!}``` +//!} +//! ``` //! Next, add a main function to launch it: //! ```rust @@ -73,7 +74,8 @@ //! .spin(SpinOptions::default()) //! .first_error() //! .map_err(|err| err.into()) -//! }``` +//! } +//! ``` //! ## Run the node //! You should now be able to run this node with `cargo build` and then `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. @@ -105,9 +107,9 @@ //! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message //! ```rust +//! use rclrs::*; //! use std::sync::{Arc, Mutex}; // (1) //! use std_msgs::msg::String as StringMsg; -//! use rclrs::*; //! struct RepublisherNode { //! _node: Arc, @@ -175,7 +177,7 @@ //! let context = Context::default_from_env()?; //! let mut executor = context.create_basic_executor(); //! let _republisher = RepublisherNode::new(&executor)?; -//! std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { +//! std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { //! loop { //! use std::time::Duration; //! std::thread::sleep(Duration::from_millis(1000)); @@ -194,7 +196,7 @@ //! because the function that the variable is coming from might return before the thread that borrows the variable ends. //! > 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. //! -//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` +//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `executor::spin()` //! and the `republish()` function only require a shared reference: //! ```rust //! fn main() -> Result<(), rclrs::RclrsError> { @@ -216,8 +218,13 @@ //!``` //! ## Try it out -//! In separate terminals, run `cargo run --bin first_rclrs_node` if running the current node or `cargo run` otherwise and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. -//! +//! ### Terminal 1: +//! In a first terminal, in the workspace root, run: +//! 1. `colcon build --packages-select examples_rclrs_minimal_pub_sub` to build the node. +//! 2. `ros2 run examples_rclrs_minimal_pub_sub first_rclrs_node` to run the node. +//! ### Terminal 2: +//! In another terminal, run `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. +//! ### Terminal 3: //! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. //! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. //! From b9c6bba8df23b43e0916c7aab2515e74df89a826 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 10:03:26 +0200 Subject: [PATCH 4/9] build: use tokusumi/markdown-embed-code@main action to synchronize Markdown files and example code Signed-off-by: Esteve Fernandez --- .github/workflows/rust-minimal.yml | 11 +++++++++++ .github/workflows/rust-stable.yml | 11 +++++++++++ 2 files changed, 22 insertions(+) diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index a93dfe318..efeaacfc4 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -36,6 +36,17 @@ jobs: image: ${{ matrix.docker_image }} steps: - uses: actions/checkout@v4 + with: + persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token + fetch-depth: 0 # otherwise, you will failed to push refs to dest repo + ref: refs/heads/${{ github.head_ref }} + + - uses: tokusumi/markdown-embed-code@main + with: + markdown: "docs/writing-your-first-rclrs-node.md" + token: ${{ secrets.GITHUB_TOKEN }} + message: "synchronizing Markdown files" + silent: true - name: Search packages in this repository id: list_packages diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index fec89e84b..baa064c87 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -36,6 +36,17 @@ jobs: image: ${{ matrix.docker_image }} steps: - uses: actions/checkout@v4 + with: + persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token + fetch-depth: 0 # otherwise, you will failed to push refs to dest repo + ref: refs/heads/${{ github.head_ref }} + + - uses: tokusumi/markdown-embed-code@main + with: + markdown: "docs/writing-your-first-rclrs-node.md" + token: ${{ secrets.GITHUB_TOKEN }} + message: "synchronizing Markdown files" + silent: true - name: Search packages in this repository id: list_packages From 50860e685395ede2c6e39c7e42a97635355511e1 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 10:48:03 +0200 Subject: [PATCH 5/9] build: reference example in tutorial Signed-off-by: Esteve Fernandez --- README.md | 2 +- docs/writing-your-first-rclrs-node.md | 201 +++++++++++++++ .../minimal_pub_sub/src/first_rclrs_node.rs | 233 +----------------- 3 files changed, 203 insertions(+), 233 deletions(-) create mode 100644 docs/writing-your-first-rclrs-node.md diff --git a/README.md b/README.md index d9e0efcf1..e05317fb8 100644 --- a/README.md +++ b/README.md @@ -71,5 +71,5 @@ ros2 launch examples_rclrs_minimal_pub_sub minimal_pub_sub.launch.xml ``` Further documentation articles: -- [Tutorial on writing your first node with `rclrs`](./examples/minimal_pub_sub/src/first_rclrs_node.rs) +- [Tutorial on writing your first node with `rclrs`](docs/writing-your-first-rclrs-node.md) - [Contributor's guide](docs/CONTRIBUTING.md) diff --git a/docs/writing-your-first-rclrs-node.md b/docs/writing-your-first-rclrs-node.md new file mode 100644 index 000000000..6ef5003ea --- /dev/null +++ b/docs/writing-your-first-rclrs-node.md @@ -0,0 +1,201 @@ +# Writing your first `rclrs` node + +This tutorial is intended to point out some of the differences of the Rust client library with the other client libraries. It assumes knowledge of Rust, and is also not intended to be an introduction to ROS 2. + +As a semi-realistic example, let's create a node that periodically republishes the last message it received. It's limited to only one specific message type – `std_msgs/msg/String` in this example. + +## Create a package + +In ROS 2, `ros2 pkg create` is the standard way of creating packages. However, the functionality to create Rust packages with this tool is not yet implemented, so they need to be created manually. + +You can start by creating a package with `cargo` in the usual way: + +```console +cargo new republisher_node && cd republisher_node +``` + +In the `Cargo.toml` file, add a dependency on `rclrs = "*"` and `std_msgs = "*"`. + +Additionally, create a new `package.xml` if you want your node to be buildable with `colcon`. Make sure to change the build type to `ament_cargo` and to include the two packages mentioned above in the dependencies, as such: + +```xml + + republisher_node + 0.0.0 + TODO: Package description + user + TODO: License declaration + + rclrs + std_msgs + + + ament_cargo + + +``` + + +## Writing the basic node structure + +Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`. + +Instead, you can store the node as a regular member. Let's add a struct that contains the node, a subscription, and a field for the last message that was received to `main.rs`: + +```rust +use std::sync::Arc; +use std_msgs::msg::String as StringMsg; + +struct RepublisherNode { + node: Arc, + _subscription: Arc>, + data: Option, +} + +impl RepublisherNode { + fn new(context: &rclrs::Context) -> Result { + let node = rclrs::Node::new(context, "republisher")?; + let data = None; + let _subscription = node.create_subscription( + "in_topic", + |msg: StringMsg| { todo!("Assign msg to self.data") }, + )?; + Ok(Self { + node, + _subscription, + data, + }) + } +} +``` + +Next, add a main function to launch it: + +```rust +fn main() -> Result<(), rclrs::RclrsError> { + let context = Context::default_from_env()?; + let mut executor = context.create_basic_executor(); + let _republisher = RepublisherNode::new(&executor)?; + executor + .spin(SpinOptions::default()) + .first_error() + .map_err(|err| err.into()) +} +``` + +You should now be able to run this node with `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. + + +## Storing received data in the struct + +Let's do something about that `todo!`. The obvious thing for the subscription callback to do would be this: + +```rust +|msg: StringMsg| { + data = Some(msg); +}, +``` + +This is a standard pattern in C++, but doesn't work in Rust. Why not? + +Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely. + +> 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. + +You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. That variable lives considerably longer, but also not forever, so it wouldn't be enough. A secondary problem is that it would be a *self-referential struct*, which is not allowed in Rust. + +The solution is _shared ownership_ of the data by the callback and the node. The `Arc` type provides shared ownership, but since it only gives out shared references to its data, we also need a `Mutex` or a `RefCell`. This `Arc>` type is a frequent pattern in Rust code. + +So, to store the received data in the struct, the following things have to change: +1. Import `Mutex` +2. Adjust the type of the `data` field +3. Create two pointers to the same data (wrapped in a `Mutex`) +4. Make the closure `move`, and inside it, lock the `Mutex` and store the message + +```rust +use rclrs::*; +use std::sync::{Arc, Mutex}; // (1) +use std_msgs::msg::String as StringMsg; +struct RepublisherNode { + _node: Arc, + _subscription: Arc>, + _data: Arc>>, // (2) +} +impl RepublisherNode { + fn new(executor: &rclrs::Executor) -> Result { + let _node = executor.create_node("republisher")?; + let _data = Arc::new(Mutex::new(None)); // (3) + let data_cb = Arc::clone(&_data); + let _subscription = _node.create_subscription( + "in_topic".keep_last(10).transient_local(), // (4) + move |msg: StringMsg| { + *data_cb.lock().unwrap() = Some(msg); + }, + )?; + Ok(Self { + _node, + _subscription, + _data, + }) + } +}``` + +If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed. + +If you couldn't follow the explanation involving borrowing, closures etc. above, an explanation of these concepts is unfortunately out of scope of this tutorial. There are many good Rust books and tutorials that can help you understand these crucial features. The online book [*The Rust Programming Language*](https://doc.rust-lang.org/book/) is a good place to start for most topics. + +## Periodically run a republishing function + +The node still doesn't republish the received messages. First, let's add a publisher to the node: + +```rust:examples/minimal_pub_sub/src/first_rclrs_node.rs [5-10] +``` + +Create a publisher and add it to the newly instantiated `RepublisherNode`: + +```rust:examples/minimal_pub_sub/src/first_rclrs_node.rs [23-29] +``` + +Then, let's add a `republish()` function to the `RepublisherNode` that publishes the latest message received, or does nothing if none was received: + +```rust:examples/minimal_pub_sub/src/first_rclrs_node.rs [32-37] +``` + +What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread: + +```rust +fn main() -> Result<(), rclrs::RclrsError> { + let context = Context::default_from_env()?; + let mut executor = context.create_basic_executor(); + let _republisher = RepublisherNode::new(&executor)?; + std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { + loop { + use std::time::Duration; + std::thread::sleep(Duration::from_millis(1000)); + _republisher.republish()?; + } + }); + executor + .spin(SpinOptions::default()) + .first_error() + .map_err(|err| err.into()) +} +``` + +But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, because the function that the variable is coming from might return before the thread that borrows the variable ends. + +> 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. + +The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()` and the `republish()` function only require a shared reference: + +```rust:examples/minimal_pub_sub/src/first_rclrs_node.rs [40-55] +``` + + +## Trying it out + +In separate terminals, run `cargo run` and `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. + +In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. + +Now publish another message, e.g. `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Servus"}' -1` and observe the `ros2 topic echo` terminal receiving that message from that point forward. diff --git a/examples/minimal_pub_sub/src/first_rclrs_node.rs b/examples/minimal_pub_sub/src/first_rclrs_node.rs index f224fab4b..c099bf77f 100644 --- a/examples/minimal_pub_sub/src/first_rclrs_node.rs +++ b/examples/minimal_pub_sub/src/first_rclrs_node.rs @@ -1,235 +1,3 @@ -//! # First rclrs node -//! This tutorial is intended to point out some of the differences of the Rust client library with the other client libraries. It assumes knowledge of Rust, and is also not intended to be an introduction to ROS 2. -//! -//! As a semi-realistic example, let's create a node that periodically republishes the last message it received. It's limited to only one specific message type – `std_msgs/msg/String` in this example. -//! -//! ## Create a package -//! In ROS 2, `ros2 pkg create` is the standard way of creating packages. However, the functionality to create Rust packages with this tool is not yet implemented, so they need to be created manually. -//! -//! You can use the current package that has already been created, or you can create a new package using `cargo` as usual: -//! ```console -//! cargo new republisher_node && cd republisher_node -//! ``` -//! In the `Cargo.toml` file, add dependencies for `rclrs = "*"` and `std_msgs = "*"`, if they are not already included. -//! -//! Additionally, a new `package.xml` needs to be created if you want your node to be buildable with `colcon` and make sure to change the build type to `ament_cargo` and to include the two packages mentioned above in the dependencies, as such: -//!```xml -//! -//! republisher_node -//! 0.0.0 -//! TODO: Package description -//! user -//! TODO: License declaration -//! -//! rclrs -//! std_msgs -//! -//! -//! ament_cargo -//! -//! -//! ``` - -//! ## Write the basic node structure -//! Since Rust doesn't have inheritance, it's not possible to inherit from `Node` as is common practice in `rclcpp` or `rclpy`. -//! -//! Instead, you can store the node as a regular member. Let's use a struct that contains the node, a subscription, and a field for the last message that was received to `main.rs`: - -//! ```rust -//! use std::sync::Arc; -//! use std_msgs::msg::String as StringMsg; -//! use rclrs::*; - -//! struct RepublisherNode { -//! _node: Arc, -//! _subscription: Arc>, -//! _data: Option, -//!} - -//! impl RepublisherNode { -//! fn new(executor: &rclrs::Executor) -> Result { -//! -//! let _node = executor.create_node("republisher")?; -//! let _data = None; -//! let _subscription = _node.create_subscription( -//! "in_topic", -//! |_msg: StringMsg| { todo!("Assign msg to self.data") }, -//! )?; -//! Ok(Self { -//! _node, -//! _subscription, -//! _data, -//! }) -//! } -//!} -//! ``` -//! Next, add a main function to launch it: - -//! ```rust -//! fn main() -> Result<(), rclrs::RclrsError> { -//! let context = Context::default_from_env()?; -//! let mut executor = context.create_basic_executor(); -//! let _republisher = RepublisherNode::new(&executor)?; -//! executor -//! .spin(SpinOptions::default()) -//! .first_error() -//! .map_err(|err| err.into()) -//! } -//! ``` - -//! ## Run the node -//! You should now be able to run this node with `cargo build` and then `cargo run`. However, the subscription callback still has a `todo!` in it, so it will exit with an error when it receives a message. - -//! ## Storing received data in the struct -//! Let's do something about that `todo!`. The obvious thing for the subscription callback to do would be this: - -//! ```rust -//! |msg: StringMsg| { -//! data = Some(msg); -//! } -//! ``` -//! This is a standard pattern in C++, but doesn't work in Rust. Why not? -//! -//! Written like this, `data` is *borrowed* by the callback, but `data` is a local variable which only exists in its current form until the end of `RepublisherNode::new()`. -//! The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely. -//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`. -//! -//! You might think "I don't want to borrow from the local variable `data` anyway, I want to borrow from the `data` field in `RepublisherNode`!" and you would be right. -//! That variable lives considerably longer, but also not forever, so it wouldn't be enough. A secondary problem is that it would be a *self-referential struct*, which is not allowed in Rust. -//! -//! The solution is _shared ownership_ of the data by the callback and the node. The `Arc` type provides shared ownership, but since it only gives out shared references to its data, -//! we also need a `Mutex` or a `RefCell`. This `Arc>` type is a frequent pattern in Rust code. -//! -//! So, to store the received data in the struct, the following things have to change: -//! 1. Import `Mutex` -//! 2. Adjust the type of the `data` field -//! 3. Create two pointers to the same data (wrapped in a `Mutex`) -//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message - -//! ```rust -//! use rclrs::*; -//! use std::sync::{Arc, Mutex}; // (1) -//! use std_msgs::msg::String as StringMsg; - -//! struct RepublisherNode { -//! _node: Arc, -//! _subscription: Arc>, -//! _data: Arc>>, // (2) -//! } - -//! impl RepublisherNode { -//! fn new(executor: &rclrs::Executor) -> Result { -//! let _node = executor.create_node("republisher")?; -//! let _data = Arc::new(Mutex::new(None)); // (3) -//! let data_cb = Arc::clone(&_data); -//! let _subscription = _node.create_subscription( -//! "in_topic".keep_last(10).transient_local(), // (4) -//! move |msg: StringMsg| { -//! *data_cb.lock().unwrap() = Some(msg); -//! }, -//! )?; -//! Ok(Self { -//! _node, -//! _subscription, -//! _data, -//! }) -//! } -//! } -//! ``` -//! -//! If that seems needlessly complicated – maybe it is, in the sense that `rclrs` could potentially introduce new abstractions to improve the ergonomics of this use case. This is to be discussed. -//! -//! If you couldn't follow the explanation involving borrowing, closures etc. above, an explanation of these concepts is unfortunately out of scope of this tutorial. -//! There are many good Rust books and tutorials that can help you understand these crucial features. The online book [*The Rust Programming Language*](https://doc.rust-lang.org/book/) is a good place to start for most topics. -//! -//! ## Periodically run a republishing function -//! -//! The node still doesn't republish the received messages. First, let's add a publisher to the node: -//! -//! ```rust -//! // Add this new field to the RepublisherNode struct, after the subscription: -//! _publisher: Arc>, -//! -//! // Change the end of RepublisherNode::new() to this: -//! let _publisher = _node.create_publisher::("out_topic")?; -//! Ok(Self { -//! _node, -//! _subscription, -//! _publisher, -//! _data, -//! }) -//! ``` -//! Then, let's add a `republish()` function to the `RepublisherNode` struct that periodically republishes the last message received, or does nothing if none was received: -//! -//! ```rust -//!fn republish(&self) -> Result<(), rclrs::RclrsError> { -//! if let Some(s) = &*self._data.lock().unwrap() { -//! self._publisher.publish(s)?; -//! } -//! Ok(()) -//! } -//! ``` -//! What's left to do is to call this function every second. `rclrs` doesn't yet have ROS timers, which run a function at a fixed interval, -//! but it's easy enough to achieve with a thread, a loop, and the sleep function. Change your main function to spawn a separate thread: -//! -//! ```rust -//! fn main() -> Result<(), rclrs::RclrsError> { -//! let context = Context::default_from_env()?; -//! let mut executor = context.create_basic_executor(); -//! let _republisher = RepublisherNode::new(&executor)?; -//! std::thread::spawn(|| -> Result<(), rclrs::RclrsError> { -//! loop { -//! use std::time::Duration; -//! std::thread::sleep(Duration::from_millis(1000)); -//! _republisher.republish()?; -//! } -//! }); -//! executor -//! .spin(SpinOptions::default()) -//! .first_error() -//! .map_err(|err| err.into()) -//! } -//! ``` -//! -//! But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`. -//! That's again the same issue as above: Rust doesn't allow borrowing variables in this closure, -//! because the function that the variable is coming from might return before the thread that borrows the variable ends. -//! > 💡 Of course, you could argue that this cannot really happen here, because returning from `main()` will also terminate the other threads, but Rust isn't that smart. -//! -//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `executor::spin()` -//! and the `republish()` function only require a shared reference: -//! ```rust -//! fn main() -> Result<(), rclrs::RclrsError> { -//! let context = Context::default_from_env()?; -//! let mut executor = context.create_basic_executor(); -//! let _republisher = RepublisherNode::new(&executor)?; -//! std::thread::spawn(move || -> Result<(), rclrs::RclrsError> { -//! loop { -//! use std::time::Duration; -//! std::thread::sleep(Duration::from_millis(1000)); -//! _republisher.republish()?; -//! } -//! }); -//! executor -//! .spin(SpinOptions::default()) -//! .first_error() -//! .map_err(|err| err.into()) -//!} -//!``` - -//! ## Try it out -//! ### Terminal 1: -//! In a first terminal, in the workspace root, run: -//! 1. `colcon build --packages-select examples_rclrs_minimal_pub_sub` to build the node. -//! 2. `ros2 run examples_rclrs_minimal_pub_sub first_rclrs_node` to run the node. -//! ### Terminal 2: -//! In another terminal, run `ros2 topic echo /out_topic`. Nothing will be shown yet, since our node hasn't received any data yet. -//! ### Terminal 3: -//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`. -//! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second. -//! -//! Now publish another message, e.g. `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Servus"}' -1` and observe the `ros2 topic echo` terminal receiving that message from that point forward. - use rclrs::*; use std::sync::{Arc, Mutex}; use std_msgs::msg::String as StringMsg; @@ -268,6 +36,7 @@ impl RepublisherNode { Ok(()) } } + fn main() -> Result<(), rclrs::RclrsError> { let context = Context::default_from_env()?; let mut executor = context.create_basic_executor(); From 5ff472d2c187ded10989a8b31d29b0196b55b62a Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 10:52:44 +0200 Subject: [PATCH 6/9] build: use fork for the sync action, upstream has not been updated in a long time Signed-off-by: Esteve Fernandez --- .github/workflows/rust-minimal.yml | 2 +- .github/workflows/rust-stable.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index efeaacfc4..0d5829e69 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -41,7 +41,7 @@ jobs: fetch-depth: 0 # otherwise, you will failed to push refs to dest repo ref: refs/heads/${{ github.head_ref }} - - uses: tokusumi/markdown-embed-code@main + - uses: technology-studio-forks/markdown-embed-code@main with: markdown: "docs/writing-your-first-rclrs-node.md" token: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index baa064c87..e5a868974 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -41,7 +41,7 @@ jobs: fetch-depth: 0 # otherwise, you will failed to push refs to dest repo ref: refs/heads/${{ github.head_ref }} - - uses: tokusumi/markdown-embed-code@main + - uses: technology-studio-forks/markdown-embed-code@main with: markdown: "docs/writing-your-first-rclrs-node.md" token: ${{ secrets.GITHUB_TOKEN }} From 0b11b2fa7109c22307393e8bb5d7cb22ec807a2e Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 10:55:29 +0200 Subject: [PATCH 7/9] fix Signed-off-by: Esteve Fernandez --- .github/workflows/rust-minimal.yml | 1 - .github/workflows/rust-stable.yml | 1 - 2 files changed, 2 deletions(-) diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index 0d5829e69..55fa0adeb 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -39,7 +39,6 @@ jobs: with: persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token fetch-depth: 0 # otherwise, you will failed to push refs to dest repo - ref: refs/heads/${{ github.head_ref }} - uses: technology-studio-forks/markdown-embed-code@main with: diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index e5a868974..8ea88f695 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -39,7 +39,6 @@ jobs: with: persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token fetch-depth: 0 # otherwise, you will failed to push refs to dest repo - ref: refs/heads/${{ github.head_ref }} - uses: technology-studio-forks/markdown-embed-code@main with: From d4015ab52cfa791fae4592880b732e4b56c3ab18 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 11:00:56 +0200 Subject: [PATCH 8/9] test Signed-off-by: Esteve Fernandez --- .github/workflows/rust-minimal.yml | 3 ++- .github/workflows/rust-stable.yml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index 55fa0adeb..923c589f1 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -35,10 +35,11 @@ jobs: container: image: ${{ matrix.docker_image }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v2 with: persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token fetch-depth: 0 # otherwise, you will failed to push refs to dest repo + ref: refs/heads/${{ github.head_ref }} - uses: technology-studio-forks/markdown-embed-code@main with: diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index 8ea88f695..c848070aa 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -35,10 +35,11 @@ jobs: container: image: ${{ matrix.docker_image }} steps: - - uses: actions/checkout@v4 + - uses: actions/checkout@v2 with: persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token fetch-depth: 0 # otherwise, you will failed to push refs to dest repo + ref: refs/heads/${{ github.head_ref }} - uses: technology-studio-forks/markdown-embed-code@main with: From d9c5cea852cd9892b278b7effc724e11cc191e5b Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Wed, 2 Apr 2025 11:03:42 +0200 Subject: [PATCH 9/9] test Signed-off-by: Esteve Fernandez --- .github/workflows/rust-minimal.yml | 6 +----- .github/workflows/rust-stable.yml | 6 +----- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/.github/workflows/rust-minimal.yml b/.github/workflows/rust-minimal.yml index 923c589f1..abc51ed4d 100644 --- a/.github/workflows/rust-minimal.yml +++ b/.github/workflows/rust-minimal.yml @@ -35,11 +35,7 @@ jobs: container: image: ${{ matrix.docker_image }} steps: - - uses: actions/checkout@v2 - with: - persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token - fetch-depth: 0 # otherwise, you will failed to push refs to dest repo - ref: refs/heads/${{ github.head_ref }} + - uses: actions/checkout@v4 - uses: technology-studio-forks/markdown-embed-code@main with: diff --git a/.github/workflows/rust-stable.yml b/.github/workflows/rust-stable.yml index c848070aa..ed054f14b 100644 --- a/.github/workflows/rust-stable.yml +++ b/.github/workflows/rust-stable.yml @@ -35,11 +35,7 @@ jobs: container: image: ${{ matrix.docker_image }} steps: - - uses: actions/checkout@v2 - with: - persist-credentials: false # otherwise, the token used is the GITHUB_TOKEN, instead of your personal token - fetch-depth: 0 # otherwise, you will failed to push refs to dest repo - ref: refs/heads/${{ github.head_ref }} + - uses: actions/checkout@v4 - uses: technology-studio-forks/markdown-embed-code@main with: