You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: examples/minimal_pub_sub/src/first_rclrs_node.rs
+76-86Lines changed: 76 additions & 86 deletions
Original file line number
Diff line number
Diff line change
@@ -5,12 +5,11 @@
5
5
//!
6
6
//! ## Create a package
7
7
//! 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.
8
-
//!
8
+
//!
9
9
//! You can use the current package that has already been created, or you can create a new package using `cargo` as usual:
10
10
//! ```console
11
11
//! cargo new republisher_node && cd republisher_node
12
12
//! ```
13
-
14
13
//! In the `Cargo.toml` file, add dependencies for `rclrs = "*"` and `std_msgs = "*"`, if they are not already included.
15
14
//!
16
15
//! 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 @@
62
61
//! _data,
63
62
//! })
64
63
//! }
65
-
//!}
66
-
//! ```
67
-
64
+
//!}```
68
65
//! Next, add a main function to launch it:
69
66
70
-
//!```rust
67
+
//!```rust
71
68
//! fn main() -> Result<(), rclrs::RclrsError> {
72
-
//! let context = Context::default_from_env()?;
73
-
//! let mut executor = context.create_basic_executor();
74
-
//! let _republisher = RepublisherNode::new(&executor)?;
75
-
//! executor
76
-
//! .spin(SpinOptions::default())
77
-
//! .first_error()
78
-
//! .map_err(|err| err.into())
79
-
//!}
80
-
//! ```
81
-
69
+
//! let context = Context::default_from_env()?;
70
+
//! let mut executor = context.create_basic_executor();
71
+
//! let _republisher = RepublisherNode::new(&executor)?;
72
+
//! executor
73
+
//! .spin(SpinOptions::default())
74
+
//! .first_error()
75
+
//! .map_err(|err| err.into())
76
+
//! }```
82
77
83
78
//! ## Run the node
84
79
//! 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 @@
89
84
//! ```rust
90
85
//! |msg: StringMsg| {
91
86
//! data = Some(msg);
92
-
//!},
93
-
//!```
94
-
95
-
87
+
//! }
88
+
//! ```
96
89
//! This is a standard pattern in C++, but doesn't work in Rust. Why not?
97
90
//!
98
-
//! 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()`.
91
+
//! 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()`.
99
92
//! The subscription callback is required to not borrow any variables because the subscription, and therefore the callback, could live indefinitely.
100
-
//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`.
93
+
//! > 💡 As an aside, this requirement is expressed by the `'static` bound on the generic parameter `F` for the callback in `Node::create_subscription()`.
101
94
//!
102
-
//! 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.
95
+
//! 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.
103
96
//! 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.
104
97
//!
105
98
//! 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 @@
109
102
//! 1. Import `Mutex`
110
103
//! 2. Adjust the type of the `data` field
111
104
//! 3. Create two pointers to the same data (wrapped in a `Mutex`)
112
-
//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message
105
+
//! 4. Make the closure `move`, and inside it, lock the `Mutex` and store the message
113
106
114
107
//! ```rust
115
108
//! use std::sync::{Arc, Mutex}; // (1)
@@ -140,20 +133,17 @@
140
133
//! })
141
134
//! }
142
135
//! }
143
-
144
136
//! ```
145
137
//!
146
-
147
138
//! 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.
148
-
//!
139
+
//!
149
140
//! 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.
150
141
//! 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.
151
-
152
-
142
+
//!
153
143
//! ## Periodically run a republishing function
154
-
//!
144
+
//!
155
145
//! The node still doesn't republish the received messages. First, let's add a publisher to the node:
156
-
146
+
//!
157
147
//! ```rust
158
148
//! // Add this new field to the RepublisherNode struct, after the subscription:
159
149
//! _publisher: Arc<rclrs::Publisher<StringMsg>>,
@@ -167,7 +157,6 @@
167
157
//! _data,
168
158
//! })
169
159
//! ```
170
-
171
160
//! 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:
172
161
//!
173
162
//! ```rust
@@ -178,36 +167,34 @@
178
167
//! Ok(())
179
168
//! }
180
169
//! ```
181
-
182
170
//! 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,
183
171
//! 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:
184
172
//!
185
173
//! ```rust
186
174
//! fn main() -> Result<(), rclrs::RclrsError> {
187
-
//! let context = Context::default_from_env()?;
188
-
//! let mut executor = context.create_basic_executor();
189
-
//! let _republisher = RepublisherNode::new(&executor)?;
//! But wait, this doesn't work – there is an error about the thread closure needing to outlive `'static`.
193
+
//! That's again the same issue as above: Rust doesn't allow borrowing variables in this closure,
207
194
//! because the function that the variable is coming from might return before the thread that borrows the variable ends.
208
195
//! > 💡 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.
209
-
//!
210
-
//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()`
196
+
//!
197
+
//! The solution is also the same as above: Shared ownership with `Arc`. Only this time, `Mutex` isn't needed since both the `rclcpp::spin()`
211
198
//! and the `republish()` function only require a shared reference:
212
199
//! ```rust
213
200
//! fn main() -> Result<(), rclrs::RclrsError> {
@@ -231,43 +218,46 @@
231
218
//! ## Try it out
232
219
//! 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.
233
220
//!
234
-
//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`.
221
+
//! In another terminal, publish a single message with `ros2 topic pub /in_topic std_msgs/msg/String '{data: "Bonjour"}' -1`.
235
222
//! The terminal with `ros2 topic echo` should now receive a new `Bonjour` message every second.
236
223
//!
237
224
//! 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.
0 commit comments