@@ -21,8 +21,9 @@ use rosidl_runtime_rs::Message;
2121use crate :: {
2222 rcl_bindings:: * , Client , ClientBase , ClientOptions , Clock , ContextHandle , GuardCondition ,
2323 ParameterBuilder , ParameterInterface , ParameterVariant , Parameters , Publisher , PublisherOptions ,
24- RclrsError , Service , ServiceBase , ServiceOptions , Subscription , SubscriptionBase , SubscriptionCallback ,
25- SubscriptionOptions , TimeSource , ENTITY_LIFECYCLE_MUTEX ,
24+ PublisherState , RclrsError , Service , ServiceBase , ServiceOptions , ServiceState , Subscription ,
25+ SubscriptionBase , SubscriptionCallback , SubscriptionOptions , SubscriptionState , TimeSource ,
26+ ENTITY_LIFECYCLE_MUTEX ,
2627} ;
2728
2829// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -39,7 +40,7 @@ unsafe impl Send for rcl_node_t {}
3940/// to exist and be displayed by e.g. `ros2 topic` as long as any one of its primitives is not dropped.
4041///
4142/// # Creating
42- /// Use [`Executor::create_node`] to create a new node. Pass in [`NodeOptions`] to set all the different
43+ /// Use [`Executor::create_node`][7] to create a new node. Pass in [`NodeOptions`] to set all the different
4344/// options for node creation, or just pass in a string for the node's name if the default options are okay.
4445///
4546/// # Naming
@@ -58,27 +59,30 @@ unsafe impl Send for rcl_node_t {}
5859/// In that sense, the parameters to the node creation functions are only the _default_ namespace and
5960/// name.
6061/// See also the [official tutorial][1] on the command line arguments for ROS nodes, and the
61- /// [`Node::namespace()`] and [`Node::name()`] functions for examples.
62+ /// [`Node::namespace()`][3] and [`Node::name()`][4 ] functions for examples.
6263///
6364/// ## Rules for valid names
6465/// The rules for valid node names and node namespaces are explained in
65- /// [`NodeBuilder ::new()`][3 ] and [`NodeBuilder ::namespace()`][4 ].
66+ /// [`NodeOptions ::new()`][5 ] and [`NodeOptions ::namespace()`][6 ].
6667///
6768/// The `Node` object is really just a shared [`NodeState`], so see the [`NodeState`]
6869/// API to see the various operations you can do with a node, such as creating
6970/// subscriptions, publishers, services, and clients.
7071///
7172/// [1]: https://docs.ros.org/en/rolling/Tutorials/Understanding-ROS2-Nodes.html
7273/// [2]: https://docs.ros.org/en/rolling/How-To-Guides/Node-arguments.html
73- /// [3]: crate::NodeBuilder::new
74- /// [4]: crate::NodeBuilder::namespace
74+ /// [3]: NodeState::namespace
75+ /// [4]: NodeState::name
76+ /// [5]: crate::NodeOptions::new
77+ /// [6]: crate::NodeOptions::namespace
78+ /// [7]: crate::Executor::create_node
7579pub type Node = Arc < NodeState > ;
7680
7781/// The inner state of a [`Node`].
7882///
7983/// This is public so that you can choose to put it inside a [`Weak`] if you
8084/// want to be able to refer to a [`Node`] in a non-owning way. It is generally
81- /// recommended to manage the [ `NodeState`] inside of an [`Arc`], and [`Node`]
85+ /// recommended to manage the `NodeState` inside of an [`Arc`], and [`Node`]
8286/// is provided as convenience alias for that.
8387///
8488/// The public API of the [`Node`] type is implemented via `NodeState`.
@@ -187,7 +191,7 @@ impl NodeState {
187191 /// Returns the fully qualified name of the node.
188192 ///
189193 /// The fully qualified name of the node is the node namespace combined with the node name.
190- /// It is subject to the remappings shown in [`Node::name()`] and [`Node::namespace()`].
194+ /// It is subject to the remappings shown in [`Node::name()`][1] and [`Node::namespace()`][2 ].
191195 ///
192196 /// # Example
193197 /// ```
@@ -200,6 +204,9 @@ impl NodeState {
200204 /// assert_eq!(node.fully_qualified_name(), "/my/namespace/my_node");
201205 /// # Ok::<(), RclrsError>(())
202206 /// ```
207+ ///
208+ /// [1]: NodeState::name
209+ /// [2]: NodeState::namespace
203210 pub fn fully_qualified_name ( & self ) -> String {
204211 self . call_string_getter ( rcl_node_get_fully_qualified_name)
205212 }
@@ -246,7 +253,9 @@ impl NodeState {
246253 /// remain the default service options. Note that clients are generally
247254 /// expected to use [reliable][2], so it's best not to change the reliability
248255 /// setting unless you know what you are doing.
256+ ///
249257 /// [1]: crate::Client
258+ /// [2]: crate::QoSReliabilityPolicy::Reliable
250259 // TODO: make client's lifetime depend on node's lifetime
251260 pub fn create_client < ' a , T > (
252261 & self ,
@@ -263,12 +272,12 @@ impl NodeState {
263272 /// Creates a [`GuardCondition`][1] with no callback.
264273 ///
265274 /// A weak pointer to the `GuardCondition` is stored within this node.
266- /// When this node is added to a wait set (e.g. when calling `spin_once` [2]
275+ /// When this node is added to a wait set (e.g. when [spinning] [2]
267276 /// with this node as an argument), the guard condition can be used to
268277 /// interrupt the wait.
269278 ///
270279 /// [1]: crate::GuardCondition
271- /// [2]: crate::spin_once
280+ /// [2]: crate::Executor::spin
272281 pub fn create_guard_condition ( & self ) -> Arc < GuardCondition > {
273282 let guard_condition = Arc :: new ( GuardCondition :: new_with_context_handle (
274283 Arc :: clone ( & self . handle . context_handle ) ,
@@ -282,12 +291,12 @@ impl NodeState {
282291 /// Creates a [`GuardCondition`][1] with a callback.
283292 ///
284293 /// A weak pointer to the `GuardCondition` is stored within this node.
285- /// When this node is added to a wait set (e.g. when calling `spin_once` [2]
294+ /// When this node is added to a wait set (e.g. when [spinning] [2]
286295 /// with this node as an argument), the guard condition can be used to
287296 /// interrupt the wait.
288297 ///
289298 /// [1]: crate::GuardCondition
290- /// [2]: crate::spin_once
299+ /// [2]: crate::Executor::spin
291300 pub fn create_guard_condition_with_callback < F > ( & mut self , callback : F ) -> Arc < GuardCondition >
292301 where
293302 F : Fn ( ) + Send + Sync + ' static ,
@@ -339,11 +348,11 @@ impl NodeState {
339348 pub fn create_publisher < ' a , T > (
340349 & self ,
341350 options : impl Into < PublisherOptions < ' a > > ,
342- ) -> Result < Arc < Publisher < T > > , RclrsError >
351+ ) -> Result < Publisher < T > , RclrsError >
343352 where
344353 T : Message ,
345354 {
346- let publisher = Arc :: new ( Publisher :: < T > :: new ( Arc :: clone ( & self . handle ) , options) ?) ;
355+ let publisher = Arc :: new ( PublisherState :: < T > :: new ( Arc :: clone ( & self . handle ) , options) ?) ;
347356 Ok ( publisher)
348357 }
349358
@@ -396,12 +405,12 @@ impl NodeState {
396405 & self ,
397406 options : impl Into < ServiceOptions < ' a > > ,
398407 callback : F ,
399- ) -> Result < Arc < Service < T > > , RclrsError >
408+ ) -> Result < Service < T > , RclrsError >
400409 where
401410 T : rosidl_runtime_rs:: Service ,
402411 F : Fn ( & rmw_request_id_t , T :: Request ) -> T :: Response + ' static + Send ,
403412 {
404- let service = Arc :: new ( Service :: < T > :: new (
413+ let service = Arc :: new ( ServiceState :: < T > :: new (
405414 Arc :: clone ( & self . handle ) ,
406415 options,
407416 callback,
@@ -460,11 +469,11 @@ impl NodeState {
460469 & self ,
461470 options : impl Into < SubscriptionOptions < ' a > > ,
462471 callback : impl SubscriptionCallback < T , Args > ,
463- ) -> Result < Arc < Subscription < T > > , RclrsError >
472+ ) -> Result < Subscription < T > , RclrsError >
464473 where
465474 T : Message ,
466475 {
467- let subscription = Arc :: new ( Subscription :: < T > :: new (
476+ let subscription = Arc :: new ( SubscriptionState :: < T > :: new (
468477 Arc :: clone ( & self . handle ) ,
469478 options,
470479 callback,
0 commit comments