Skip to main content

StandaloneNode

Struct StandaloneNode 

Source
pub struct StandaloneNode<const MAX_PUBS: usize = 8, const MAX_SUBS: usize = 8> { /* private fields */ }
Expand description

ROS 2 Node for embedded systems

The node manages publishers and subscribers with static allocation. MAX_PUBS and MAX_SUBS define the maximum number of publishers and subscribers that can be created.

§Type Parameters

  • MAX_PUBS: Maximum number of publishers
  • MAX_SUBS: Maximum number of subscribers

Implementations§

Source§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Node<MAX_PUBS, MAX_SUBS>

Source

pub fn new( config: NodeConfig<'_>, ) -> Result<Node<MAX_PUBS, MAX_SUBS>, NodeError>

Create a new node with the given configuration

Source

pub fn name(&self) -> &str

Get the node name

Source

pub fn namespace(&self) -> &str

Get the node namespace

Source

pub fn domain_id(&self) -> u32

Get the domain ID

Source

pub fn fully_qualified_name(&self) -> Result<String<128>, NodeError>

Get the fully qualified node name.

Phase 192.1 — fallible: namespace (≤64) + / + name (≤64) can reach 129 bytes, one over the String<128> capacity, so a maxed name+namespace would otherwise silently truncate the FQN.

Source

pub fn create_publisher<M>( &mut self, options: PublisherOptions<'_>, ) -> Result<PublisherHandle<M>, NodeError>
where M: RosMessage,

Create a publisher with the given options

Source

pub fn create_subscriber<M>( &mut self, options: SubscriberOptions<'_>, ) -> Result<SubscriberHandle<M>, NodeError>
where M: RosMessage,

Create a subscriber with the given options

Source

pub fn publisher_topic_info( &self, handle: PublisherHandle<()>, ) -> Option<TopicInfo<'_>>

Get topic info for a publisher

Source

pub fn subscriber_topic_info( &self, handle: SubscriberHandle<()>, ) -> Option<TopicInfo<'_>>

Get topic info for a subscriber

Source

pub fn serialize_message<M>( &mut self, _handle: &PublisherHandle<M>, msg: &M, ) -> Result<&[u8], NodeError>
where M: RosMessage,

Serialize a message for publishing

Returns the serialized bytes. The caller is responsible for sending the bytes via the transport layer.

Source

pub fn deserialize_message<M>( &self, _handle: &SubscriberHandle<M>, data: &[u8], ) -> Result<M, NodeError>
where M: RosMessage,

Deserialize a received message

The caller provides the raw bytes received from the transport layer.

Source

pub fn publisher_count(&self) -> usize

Get the number of active publishers

Source

pub fn subscriber_count(&self) -> usize

Get the number of active subscribers

Trait Implementations§

Source§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Default for Node<MAX_PUBS, MAX_SUBS>

Source§

fn default() -> Node<MAX_PUBS, MAX_SUBS>

Returns the “default value” for a type. Read more

Auto Trait Implementations§

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Freeze for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> RefUnwindSafe for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Send for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Sync for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> Unpin for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> UnsafeUnpin for Node<MAX_PUBS, MAX_SUBS>

§

impl<const MAX_PUBS: usize, const MAX_SUBS: usize> UnwindSafe for Node<MAX_PUBS, MAX_SUBS>

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.