do_not_use_testing_rclrs/node.rs
1mod builder;
2mod graph;
3use std::cmp::PartialEq;
4use std::ffi::CStr;
5use std::fmt;
6use std::os::raw::c_char;
7use std::sync::{Arc, Mutex, Weak};
8use std::vec::Vec;
9
10use rosidl_runtime_rs::Message;
11
12pub use self::builder::*;
13pub use self::graph::*;
14use crate::rcl_bindings::*;
15use crate::{
16 Client, ClientBase, Clock, Context, GuardCondition, ParameterBuilder, ParameterInterface,
17 ParameterVariant, Parameters, Publisher, QoSProfile, RclrsError, Service, ServiceBase,
18 Subscription, SubscriptionBase, SubscriptionCallback, TimeSource, ToResult,
19};
20
21impl Drop for rcl_node_t {
22 fn drop(&mut self) {
23 // SAFETY: No preconditions for this function
24 unsafe { rcl_node_fini(self).ok().unwrap() };
25 }
26}
27
28// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
29// they are running in. Therefore, this type can be safely sent to another thread.
30unsafe impl Send for rcl_node_t {}
31
32/// A processing unit that can communicate with other nodes.
33///
34/// Nodes are a core concept in ROS 2. Refer to the official ["Understanding ROS 2 nodes"][1]
35/// tutorial for an introduction.
36///
37/// Ownership of the node is shared with all [`Publisher`]s and [`Subscription`]s created from it.
38/// That means that even after the node itself is dropped, it will continue to exist and be
39/// displayed by e.g. `ros2 topic` as long as its publishers and subscriptions are not dropped.
40///
41/// # Naming
42/// A node has a *name* and a *namespace*.
43/// The node namespace will be prefixed to the node name to form the *fully qualified
44/// node name*. This is the name that is shown e.g. in `ros2 node list`.
45/// Similarly, the node namespace will be prefixed to all names of topics and services
46/// created from this node.
47///
48/// By convention, a node name with a leading underscore marks the node as hidden.
49///
50/// It's a good idea for node names in the same executable to be unique.
51///
52/// ## Remapping
53/// The namespace and name given when creating the node can be overriden through the command line.
54/// In that sense, the parameters to the node creation functions are only the _default_ namespace and
55/// name.
56/// See also the [official tutorial][1] on the command line arguments for ROS nodes, and the
57/// [`Node::namespace()`] and [`Node::name()`] functions for examples.
58///
59/// ## Rules for valid names
60/// The rules for valid node names and node namespaces are explained in
61/// [`NodeBuilder::new()`][3] and [`NodeBuilder::namespace()`][4].
62///
63/// [1]: https://docs.ros.org/en/rolling/Tutorials/Understanding-ROS2-Nodes.html
64/// [2]: https://docs.ros.org/en/rolling/How-To-Guides/Node-arguments.html
65/// [3]: crate::NodeBuilder::new
66/// [4]: crate::NodeBuilder::namespace
67pub struct Node {
68 pub(crate) rcl_node_mtx: Arc<Mutex<rcl_node_t>>,
69 pub(crate) rcl_context_mtx: Arc<Mutex<rcl_context_t>>,
70 pub(crate) clients_mtx: Mutex<Vec<Weak<dyn ClientBase>>>,
71 pub(crate) guard_conditions_mtx: Mutex<Vec<Weak<GuardCondition>>>,
72 pub(crate) services_mtx: Mutex<Vec<Weak<dyn ServiceBase>>>,
73 pub(crate) subscriptions_mtx: Mutex<Vec<Weak<dyn SubscriptionBase>>>,
74 _time_source: TimeSource,
75 _parameter: ParameterInterface,
76}
77
78impl Eq for Node {}
79
80impl PartialEq for Node {
81 fn eq(&self, other: &Self) -> bool {
82 Arc::ptr_eq(&self.rcl_node_mtx, &other.rcl_node_mtx)
83 }
84}
85
86impl fmt::Debug for Node {
87 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> {
88 f.debug_struct("Node")
89 .field("fully_qualified_name", &self.fully_qualified_name())
90 .finish()
91 }
92}
93
94impl Node {
95 /// Creates a new node in the empty namespace.
96 ///
97 /// See [`NodeBuilder::new()`] for documentation.
98 #[allow(clippy::new_ret_no_self)]
99 pub fn new(context: &Context, node_name: &str) -> Result<Arc<Node>, RclrsError> {
100 Self::builder(context, node_name).build()
101 }
102
103 /// Returns the clock associated with this node.
104 pub fn get_clock(&self) -> Clock {
105 self._time_source.get_clock()
106 }
107
108 /// Returns the name of the node.
109 ///
110 /// This returns the name after remapping, so it is not necessarily the same as the name that
111 /// was used when creating the node.
112 ///
113 /// # Example
114 /// ```
115 /// # use rclrs::{Context, RclrsError};
116 /// // Without remapping
117 /// let context = Context::new([])?;
118 /// let node = rclrs::create_node(&context, "my_node")?;
119 /// assert_eq!(node.name(), "my_node");
120 /// // With remapping
121 /// let remapping = ["--ros-args", "-r", "__node:=your_node"].map(String::from);
122 /// let context_r = Context::new(remapping)?;
123 /// let node_r = rclrs::create_node(&context_r, "my_node")?;
124 /// assert_eq!(node_r.name(), "your_node");
125 /// # Ok::<(), RclrsError>(())
126 /// ```
127 pub fn name(&self) -> String {
128 self.call_string_getter(rcl_node_get_name)
129 }
130
131 /// Returns the namespace of the node.
132 ///
133 /// This returns the namespace after remapping, so it is not necessarily the same as the
134 /// namespace that was used when creating the node.
135 ///
136 /// # Example
137 /// ```
138 /// # use rclrs::{Context, RclrsError};
139 /// // Without remapping
140 /// let context = Context::new([])?;
141 /// let node =
142 /// rclrs::create_node_builder(&context, "my_node")
143 /// .namespace("/my/namespace")
144 /// .build()?;
145 /// assert_eq!(node.namespace(), "/my/namespace");
146 /// // With remapping
147 /// let remapping = ["--ros-args", "-r", "__ns:=/your_namespace"].map(String::from);
148 /// let context_r = Context::new(remapping)?;
149 /// let node_r = rclrs::create_node(&context_r, "my_node")?;
150 /// assert_eq!(node_r.namespace(), "/your_namespace");
151 /// # Ok::<(), RclrsError>(())
152 /// ```
153 pub fn namespace(&self) -> String {
154 self.call_string_getter(rcl_node_get_namespace)
155 }
156
157 /// Returns the fully qualified name of the node.
158 ///
159 /// The fully qualified name of the node is the node namespace combined with the node name.
160 /// It is subject to the remappings shown in [`Node::name()`] and [`Node::namespace()`].
161 ///
162 /// # Example
163 /// ```
164 /// # use rclrs::{Context, RclrsError};
165 /// let context = Context::new([])?;
166 /// let node =
167 /// rclrs::create_node_builder(&context, "my_node")
168 /// .namespace("/my/namespace")
169 /// .build()?;
170 /// assert_eq!(node.fully_qualified_name(), "/my/namespace/my_node");
171 /// # Ok::<(), RclrsError>(())
172 /// ```
173 pub fn fully_qualified_name(&self) -> String {
174 self.call_string_getter(rcl_node_get_fully_qualified_name)
175 }
176
177 // Helper for name(), namespace(), fully_qualified_name()
178 fn call_string_getter(
179 &self,
180 getter: unsafe extern "C" fn(*const rcl_node_t) -> *const c_char,
181 ) -> String {
182 unsafe { call_string_getter_with_handle(&self.rcl_node_mtx.lock().unwrap(), getter) }
183 }
184
185 /// Creates a [`Client`][1].
186 ///
187 /// [1]: crate::Client
188 // TODO: make client's lifetime depend on node's lifetime
189 pub fn create_client<T>(&self, topic: &str) -> Result<Arc<Client<T>>, RclrsError>
190 where
191 T: rosidl_runtime_rs::Service,
192 {
193 let client = Arc::new(Client::<T>::new(Arc::clone(&self.rcl_node_mtx), topic)?);
194 { self.clients_mtx.lock().unwrap() }.push(Arc::downgrade(&client) as Weak<dyn ClientBase>);
195 Ok(client)
196 }
197
198 /// Creates a [`GuardCondition`][1] with no callback.
199 ///
200 /// A weak pointer to the `GuardCondition` is stored within this node.
201 /// When this node is added to a wait set (e.g. when calling `spin_once`[2]
202 /// with this node as an argument), the guard condition can be used to
203 /// interrupt the wait.
204 ///
205 /// [1]: crate::GuardCondition
206 /// [2]: crate::spin_once
207 pub fn create_guard_condition(&self) -> Arc<GuardCondition> {
208 let guard_condition = Arc::new(GuardCondition::new_with_rcl_context(
209 &mut self.rcl_context_mtx.lock().unwrap(),
210 None,
211 ));
212 { self.guard_conditions_mtx.lock().unwrap() }
213 .push(Arc::downgrade(&guard_condition) as Weak<GuardCondition>);
214 guard_condition
215 }
216
217 /// Creates a [`GuardCondition`][1] with a callback.
218 ///
219 /// A weak pointer to the `GuardCondition` is stored within this node.
220 /// When this node is added to a wait set (e.g. when calling `spin_once`[2]
221 /// with this node as an argument), the guard condition can be used to
222 /// interrupt the wait.
223 ///
224 /// [1]: crate::GuardCondition
225 /// [2]: crate::spin_once
226 pub fn create_guard_condition_with_callback<F>(&mut self, callback: F) -> Arc<GuardCondition>
227 where
228 F: Fn() + Send + Sync + 'static,
229 {
230 let guard_condition = Arc::new(GuardCondition::new_with_rcl_context(
231 &mut self.rcl_context_mtx.lock().unwrap(),
232 Some(Box::new(callback) as Box<dyn Fn() + Send + Sync>),
233 ));
234 { self.guard_conditions_mtx.lock().unwrap() }
235 .push(Arc::downgrade(&guard_condition) as Weak<GuardCondition>);
236 guard_condition
237 }
238
239 /// Creates a [`Publisher`][1].
240 ///
241 /// [1]: crate::Publisher
242 // TODO: make publisher's lifetime depend on node's lifetime
243 pub fn create_publisher<T>(
244 &self,
245 topic: &str,
246 qos: QoSProfile,
247 ) -> Result<Arc<Publisher<T>>, RclrsError>
248 where
249 T: Message,
250 {
251 let publisher = Arc::new(Publisher::<T>::new(
252 Arc::clone(&self.rcl_node_mtx),
253 topic,
254 qos,
255 )?);
256 Ok(publisher)
257 }
258
259 /// Creates a [`Service`][1].
260 ///
261 /// [1]: crate::Service
262 // TODO: make service's lifetime depend on node's lifetime
263 pub fn create_service<T, F>(
264 &self,
265 topic: &str,
266 callback: F,
267 ) -> Result<Arc<Service<T>>, RclrsError>
268 where
269 T: rosidl_runtime_rs::Service,
270 F: Fn(&rmw_request_id_t, T::Request) -> T::Response + 'static + Send,
271 {
272 let service = Arc::new(Service::<T>::new(
273 Arc::clone(&self.rcl_node_mtx),
274 topic,
275 callback,
276 )?);
277 { self.services_mtx.lock().unwrap() }
278 .push(Arc::downgrade(&service) as Weak<dyn ServiceBase>);
279 Ok(service)
280 }
281
282 /// Creates a [`Subscription`][1].
283 ///
284 /// [1]: crate::Subscription
285 // TODO: make subscription's lifetime depend on node's lifetime
286 pub fn create_subscription<T, Args>(
287 &self,
288 topic: &str,
289 qos: QoSProfile,
290 callback: impl SubscriptionCallback<T, Args>,
291 ) -> Result<Arc<Subscription<T>>, RclrsError>
292 where
293 T: Message,
294 {
295 let subscription = Arc::new(Subscription::<T>::new(
296 Arc::clone(&self.rcl_node_mtx),
297 topic,
298 qos,
299 callback,
300 )?);
301 { self.subscriptions_mtx.lock() }
302 .unwrap()
303 .push(Arc::downgrade(&subscription) as Weak<dyn SubscriptionBase>);
304 Ok(subscription)
305 }
306
307 /// Returns the subscriptions that have not been dropped yet.
308 pub(crate) fn live_subscriptions(&self) -> Vec<Arc<dyn SubscriptionBase>> {
309 { self.subscriptions_mtx.lock().unwrap() }
310 .iter()
311 .filter_map(Weak::upgrade)
312 .collect()
313 }
314
315 pub(crate) fn live_clients(&self) -> Vec<Arc<dyn ClientBase>> {
316 { self.clients_mtx.lock().unwrap() }
317 .iter()
318 .filter_map(Weak::upgrade)
319 .collect()
320 }
321
322 pub(crate) fn live_guard_conditions(&self) -> Vec<Arc<GuardCondition>> {
323 { self.guard_conditions_mtx.lock().unwrap() }
324 .iter()
325 .filter_map(Weak::upgrade)
326 .collect()
327 }
328
329 pub(crate) fn live_services(&self) -> Vec<Arc<dyn ServiceBase>> {
330 { self.services_mtx.lock().unwrap() }
331 .iter()
332 .filter_map(Weak::upgrade)
333 .collect()
334 }
335
336 /// Returns the ROS domain ID that the node is using.
337 ///
338 /// The domain ID controls which nodes can send messages to each other, see the [ROS 2 concept article][1].
339 /// It can be set through the `ROS_DOMAIN_ID` environment variable.
340 ///
341 /// [1]: https://docs.ros.org/en/rolling/Concepts/About-Domain-ID.html
342 ///
343 /// # Example
344 /// ```
345 /// # use rclrs::{Context, RclrsError};
346 /// // Set default ROS domain ID to 10 here
347 /// std::env::set_var("ROS_DOMAIN_ID", "10");
348 /// let context = Context::new([])?;
349 /// let node = rclrs::create_node(&context, "domain_id_node")?;
350 /// let domain_id = node.domain_id();
351 /// assert_eq!(domain_id, 10);
352 /// # Ok::<(), RclrsError>(())
353 /// ```
354 // TODO: If node option is supported,
355 // add description about this function is for getting actual domain_id
356 // and about override of domain_id via node option
357 pub fn domain_id(&self) -> usize {
358 let rcl_node = &*self.rcl_node_mtx.lock().unwrap();
359 let mut domain_id: usize = 0;
360 let ret = unsafe {
361 // SAFETY: No preconditions for this function.
362 rcl_node_get_domain_id(rcl_node, &mut domain_id)
363 };
364
365 debug_assert_eq!(ret, 0);
366 domain_id
367 }
368
369 /// Creates a [`ParameterBuilder`] that can be used to set parameter declaration options and
370 /// declare a parameter as [`OptionalParameter`](crate::parameter::OptionalParameter),
371 /// [`MandatoryParameter`](crate::parameter::MandatoryParameter), or
372 /// [`ReadOnly`](crate::parameter::ReadOnlyParameter).
373 ///
374 /// # Example
375 /// ```
376 /// # use rclrs::{Context, ParameterRange, RclrsError};
377 /// let context = Context::new([])?;
378 /// let node = rclrs::create_node(&context, "domain_id_node")?;
379 /// // Set it to a range of 0-100, with a step of 2
380 /// let range = ParameterRange {
381 /// lower: Some(0),
382 /// upper: Some(100),
383 /// step: Some(2),
384 /// };
385 /// let param = node.declare_parameter("int_param")
386 /// .default(10)
387 /// .range(range)
388 /// .mandatory()
389 /// .unwrap();
390 /// assert_eq!(param.get(), 10);
391 /// param.set(50).unwrap();
392 /// assert_eq!(param.get(), 50);
393 /// // Out of range, will return an error
394 /// assert!(param.set(200).is_err());
395 /// # Ok::<(), RclrsError>(())
396 /// ```
397 pub fn declare_parameter<'a, T: ParameterVariant + 'a>(
398 &'a self,
399 name: impl Into<Arc<str>>,
400 ) -> ParameterBuilder<'a, T> {
401 self._parameter.declare(name.into())
402 }
403
404 /// Enables usage of undeclared parameters for this node.
405 ///
406 /// Returns a [`Parameters`] struct that can be used to get and set all parameters.
407 pub fn use_undeclared_parameters(&self) -> Parameters {
408 self._parameter.allow_undeclared();
409 Parameters {
410 interface: &self._parameter,
411 }
412 }
413
414 /// Creates a [`NodeBuilder`][1] with the given name.
415 ///
416 /// Convenience function equivalent to [`NodeBuilder::new()`][2].
417 ///
418 /// [1]: crate::NodeBuilder
419 /// [2]: crate::NodeBuilder::new
420 ///
421 /// # Example
422 /// ```
423 /// # use rclrs::{Context, Node, RclrsError};
424 /// let context = Context::new([])?;
425 /// let node = Node::builder(&context, "my_node").build()?;
426 /// assert_eq!(node.name(), "my_node");
427 /// # Ok::<(), RclrsError>(())
428 /// ```
429 pub fn builder(context: &Context, node_name: &str) -> NodeBuilder {
430 NodeBuilder::new(context, node_name)
431 }
432}
433
434// Helper used to implement call_string_getter(), but also used to get the FQN in the Node::new()
435// function, which is why it's not merged into Node::call_string_getter().
436// This function is unsafe since it's possible to pass in an rcl_node_t with dangling
437// pointers etc.
438pub(crate) unsafe fn call_string_getter_with_handle(
439 rcl_node: &rcl_node_t,
440 getter: unsafe extern "C" fn(*const rcl_node_t) -> *const c_char,
441) -> String {
442 let char_ptr = getter(rcl_node);
443 debug_assert!(!char_ptr.is_null());
444 // SAFETY: The returned CStr is immediately converted to an owned string,
445 // so the lifetime is no issue. The ptr is valid as per the documentation
446 // of rcl_node_get_name.
447 let cstr = CStr::from_ptr(char_ptr);
448 cstr.to_string_lossy().into_owned()
449}
450
451#[cfg(test)]
452mod tests {
453 use super::*;
454
455 fn assert_send<T: Send>() {}
456 fn assert_sync<T: Sync>() {}
457
458 #[test]
459 fn node_is_send_and_sync() {
460 assert_send::<Node>();
461 assert_sync::<Node>();
462 }
463}