Struct ros2_client::Context

source ·
pub struct Context { /* private fields */ }
Expand description

Context communicates with other participants information in ROS2 network. It keeps track of NodeEntitiesInfos. Also acts as a wrapper for a RustDDS instance.

Context is shut down by dropping it, and all of its RosNodes. There should be no need for ok() or shutdown() methods.

Implementations§

source§

impl Context

source

pub fn new() -> CreateResult<Context>

Create a new Context with default settings.

source

pub fn with_options(opt: ContextOptions) -> CreateResult<Context>

Create a new Context.

source

pub fn from_domain_participant( domain_participant: DomainParticipant ) -> CreateResult<Context>

Create a new Context from an existing DomainParticipant.

source

pub fn new_node( &self, node_name: NodeName, options: NodeOptions ) -> CreateResult<Node>

Create a new ROS2 Node

source

pub fn domain_id(&self) -> u16

Query which DDS Domain Id we are using.

source

pub fn discovered_topics(&self) -> Vec<DiscoveredTopicData>

Which topics have been discovered?

source

pub fn participant_entities_info(&self) -> ParticipantEntitiesInfo

Gets the ParticipantEntitiesInfo describing the current state of this Context. This is what we send to ROS Discovery.

source

pub fn get_parameter_events_topic(&self) -> Topic

Get a (handle to) the ROSOut logging Topic.

source

pub fn get_rosout_topic(&self) -> Topic

Get a (handle to) the ROSOut logging Topic.

Note: The recommended way to write log messages to ROSOut is via the crate::rosout macro.

source

pub fn domain_participant(&self) -> DomainParticipant

Get the contained DDS DomainParticipant.

The return value is owned, but it is just a cloned smart pointer.

Trait Implementations§

source§

impl Clone for Context

source§

fn clone(&self) -> Context

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more

Auto Trait Implementations§

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> ToOwned for T
where T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

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

§

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>,

§

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.
§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

§

fn vzip(self) -> V