rclrs

Struct Node

Source
pub struct Node { /* private fields */ }
Expand description

A processing unit that can communicate with other nodes.

Nodes are a core concept in ROS 2. Refer to the official “Understanding ROS 2 nodes” tutorial for an introduction.

Ownership of the node is shared with all the primitives such as Publishers and Subscriptions that are created from it. That means that even after the Node itself is dropped, it will continue to exist and be displayed by e.g. ros2 topic as long as any one of its primitives is not dropped.

§Creating

Use Executor::create_node to create a new node. Pass in NodeOptions to set all the different options for node creation, or just pass in a string for the node’s name if the default options are okay.

§Naming

A node has a name and a namespace. The node namespace will be prefixed to the node name to form the fully qualified node name. This is the name that is shown e.g. in ros2 node list. Similarly, the node namespace will be prefixed to all names of topics and services created from this node.

By convention, a node name with a leading underscore marks the node as hidden.

It’s a good idea for node names in the same executable to be unique.

§Remapping

The namespace and name given when creating the node can be overridden through the command line. In that sense, the parameters to the node creation functions are only the default namespace and name. See also the official tutorial on the command line arguments for ROS nodes, and the Node::namespace() and Node::name() functions for examples.

§Rules for valid names

The rules for valid node names and node namespaces are explained in NodeOptions::new() and NodeOptions::namespace().

Implementations§

Source§

impl Node

Source

pub fn get_publisher_names_and_types_by_node( &self, node: &str, namespace: &str, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of topic names and types for publishers associated with a node.

Source

pub fn get_subscription_names_and_types_by_node( &self, node: &str, namespace: &str, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of topic names and types for subscriptions associated with a node.

Source

pub fn get_service_names_and_types_by_node( &self, node: &str, namespace: &str, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of topic names and types for services associated with a node.

Source

pub fn get_client_names_and_types_by_node( &self, node: &str, namespace: &str, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of topic names and types for clients associated with a node.

Source

pub fn get_topic_names_and_types( &self, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of all topic names and their types.

Source

pub fn get_service_names_and_types( &self, ) -> Result<TopicNamesAndTypes, RclrsError>

Returns a list of service names and types for this node.

Source

pub fn get_node_names(&self) -> Result<Vec<NodeNameInfo>, RclrsError>

Returns a list of all node names.

Source

pub fn get_node_names_with_enclaves( &self, ) -> Result<Vec<(NodeNameInfo, String)>, RclrsError>

Returns a list of all node names with enclaves.

Source

pub fn count_publishers(&self, topic: &str) -> Result<usize, RclrsError>

Counts the number of publishers for a given topic.

Source

pub fn count_subscriptions(&self, topic: &str) -> Result<usize, RclrsError>

Counts the number of subscriptions for a given topic.

Source

pub fn get_publishers_info_by_topic( &self, topic: &str, ) -> Result<Vec<TopicEndpointInfo>, RclrsError>

Returns topic publisher info.

Source

pub fn get_subscriptions_info_by_topic( &self, topic: &str, ) -> Result<Vec<TopicEndpointInfo>, RclrsError>

Returns topic subscriptions info.

Source§

impl Node

Source

pub fn get_clock(&self) -> Clock

Returns the clock associated with this node.

Source

pub fn name(&self) -> String

Returns the name of the node.

This returns the name after remapping, so it is not necessarily the same as the name that was used when creating the node.

§Example
// Without remapping
let executor = Context::default().create_basic_executor();
let node = executor.create_node("my_node")?;
assert_eq!(node.name(), "my_node");
// With remapping
let remapping = ["--ros-args", "-r", "__node:=your_node"].map(String::from);
let executor_r = Context::new(remapping, InitOptions::default())?.create_basic_executor();
let node_r = executor_r.create_node("my_node")?;
assert_eq!(node_r.name(), "your_node");
Source

pub fn namespace(&self) -> String

Returns the namespace of the node.

This returns the namespace after remapping, so it is not necessarily the same as the namespace that was used when creating the node.

§Example
// Without remapping
let executor = Context::default().create_basic_executor();
let node = executor.create_node(
    "my_node"
    .namespace("/my/namespace")
)?;
assert_eq!(node.namespace(), "/my/namespace");
// With remapping
let remapping = ["--ros-args", "-r", "__ns:=/your_namespace"].map(String::from);
let executor_r = Context::new(remapping, InitOptions::default())?.create_basic_executor();
let node_r = executor_r.create_node("my_node")?;
assert_eq!(node_r.namespace(), "/your_namespace");
Source

pub fn fully_qualified_name(&self) -> String

Returns the fully qualified name of the node.

The fully qualified name of the node is the node namespace combined with the node name. It is subject to the remappings shown in Node::name() and Node::namespace().

§Example
let executor = Context::default().create_basic_executor();
let node = executor.create_node(
    "my_node"
    .namespace("/my/namespace")
)?;
assert_eq!(node.fully_qualified_name(), "/my/namespace/my_node");
Source

pub fn create_client<T>( &self, topic: &str, ) -> Result<Arc<Client<T>>, RclrsError>
where T: Service,

Creates a Client.

Source

pub fn create_guard_condition(&self) -> Arc<GuardCondition>

Creates a GuardCondition with no callback.

A weak pointer to the GuardCondition is stored within this node. When this node is added to a wait set (e.g. when its executor is spinning), the guard condition can be used to interrupt the wait.

Source

pub fn create_guard_condition_with_callback<F>( &mut self, callback: F, ) -> Arc<GuardCondition>
where F: Fn() + Send + Sync + 'static,

Creates a GuardCondition with a callback.

A weak pointer to the GuardCondition is stored within this node. When this node is added to a wait set (e.g. when its executor is spinning), the guard condition can be used to interrupt the wait.

Source

pub fn create_publisher<T>( &self, topic: &str, qos: QoSProfile, ) -> Result<Arc<Publisher<T>>, RclrsError>
where T: Message,

Creates a Publisher.

Source

pub fn create_service<T, F>( &self, topic: &str, callback: F, ) -> Result<Arc<Service<T>>, RclrsError>
where T: Service, F: Fn(&rmw_request_id_t, T::Request) -> T::Response + 'static + Send,

Creates a Service.

Source

pub fn create_subscription<T, Args>( &self, topic: &str, qos: QoSProfile, callback: impl SubscriptionCallback<T, Args>, ) -> Result<Arc<Subscription<T>>, RclrsError>
where T: Message,

Creates a Subscription.

Source

pub fn domain_id(&self) -> usize

Returns the ROS domain ID that the node is using.

The domain ID controls which nodes can send messages to each other, see the ROS 2 concept article. It can be set through the ROS_DOMAIN_ID environment variable or by passing custom NodeOptions into Context::new or Context::from_env.

§Example
// Set default ROS domain ID to 10 here
std::env::set_var("ROS_DOMAIN_ID", "10");
let executor = Context::default().create_basic_executor();
let node = executor.create_node("domain_id_node")?;
let domain_id = node.domain_id();
assert_eq!(domain_id, 10);
Source

pub fn declare_parameter<'a, T: ParameterVariant + 'a>( &'a self, name: impl Into<Arc<str>>, ) -> ParameterBuilder<'a, T>

Creates a ParameterBuilder that can be used to set parameter declaration options and declare a parameter as OptionalParameter, MandatoryParameter, or ReadOnly.

§Example
let executor = Context::default().create_basic_executor();
let node = executor.create_node("domain_id_node")?;
// Set it to a range of 0-100, with a step of 2
let range = ParameterRange {
    lower: Some(0),
    upper: Some(100),
    step: Some(2),
};
let param = node.declare_parameter("int_param")
                .default(10)
                .range(range)
                .mandatory()
                .unwrap();
assert_eq!(param.get(), 10);
param.set(50).unwrap();
assert_eq!(param.get(), 50);
// Out of range, will return an error
assert!(param.set(200).is_err());
Source

pub fn use_undeclared_parameters(&self) -> Parameters<'_>

Enables usage of undeclared parameters for this node.

Returns a Parameters struct that can be used to get and set all parameters.

Source

pub fn logger(&self) -> &Logger

Get the logger associated with this Node.

Trait Implementations§

Source§

impl Debug for Node

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result<(), Error>

Formats the value using the given formatter. Read more
Source§

impl PartialEq for Node

Source§

fn eq(&self, other: &Self) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl<'a> ToLogParams<'a> for &'a Node

Source§

fn to_log_params(self) -> LogParams<'a>

Convert the object into LogParams with default settings
Source§

fn once(self) -> LogParams<'a>

The logging should only happen once
Source§

fn skip_first(self) -> LogParams<'a>

The first time the logging happens, we should skip it
Source§

fn occurs(self, occurs: LogOccurrence) -> LogParams<'a>

Set the occurrence behavior of the log instance
Source§

fn throttle(self, throttle: Duration) -> LogParams<'a>

Set a throttling interval during which this log will not publish. A value of zero will never block the message from being published, and this is the default behavior. Read more
Source§

fn throttle_clock(self, clock: ThrottleClock<'a>) -> LogParams<'a>

Set the clock that will be used to control throttling.
Source§

fn only_if(self, only_if: bool) -> LogParams<'a>

The log will not be published if a false expression is passed into this function. Read more
Source§

fn debug(self) -> LogParams<'a>

Log as a debug message.
Source§

fn info(self) -> LogParams<'a>

Log as an informative message. This is the default, so you don’t generally need to use this.
Source§

fn warn(self) -> LogParams<'a>

Log as a warning message.
Source§

fn error(self) -> LogParams<'a>

Log as an error message.
Source§

fn fatal(self) -> LogParams<'a>

Log as a fatal message.
Source§

fn severity(self, severity: LogSeverity) -> LogParams<'a>

Set the severity for this instance of logging. The default value will be [LogSeverity::Info].
Source§

impl Eq for Node

Auto Trait Implementations§

§

impl !Freeze for Node

§

impl RefUnwindSafe for Node

§

impl Send for Node

§

impl Sync for Node

§

impl Unpin for Node

§

impl UnwindSafe for Node

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.