Struct ros2_client::Node

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

Node in ROS2 network. Holds necessary readers and writers for rosout and parameter events topics internally.

These are produced by a Context.

Implementations§

source§

impl Node

source

pub fn time_now(&self) -> ROSTime

Return the ROSTime

It is either the system clock time

source

pub fn time_now_not_simulated(&self) -> ROSTime

source

pub fn spinner(&mut self) -> CreateResult<Spinner>

Create a Spinner object to execute Node backround tasks.

An async task should then be created to run the .spin() function of Spinner.

E.g. executor.spawn(node.spinner().spin())

The .spin() task runs until Node is dropped.

source

pub fn have_spinner(&self) -> bool

A heuristic to detect if a spinner has been created. But this does still not guarantee that it is running, i.e. an async excutor is runnning spinner.spin(), but this is the best we can do.

source

pub fn base_name(&self) -> &str

source

pub fn namespace(&self) -> &str

source

pub fn fully_qualified_name(&self) -> String

source

pub fn options(&self) -> &NodeOptions

source

pub fn domain_id(&self) -> u16

source

pub fn undeclare_parameter(&self, name: &str)

source

pub fn has_parameter(&self, name: &str) -> bool

Does the parameter exist?

source

pub fn set_parameter( &self, name: &str, value: ParameterValue ) -> Result<(), String>

Sets a parameter value. Parameter must be declared before setting.

source

pub fn allow_undeclared_parameters(&self) -> bool

source

pub fn get_parameter(&self, name: &str) -> Option<ParameterValue>

Gets the value of a parameter, or None is there is no such Parameter.

source

pub fn list_parameters(&self) -> Vec<String>

source

pub fn status_receiver(&self) -> Receiver<NodeEvent>

Get an async Receiver for discovery events.

There must be an async task executing spin to get any data.

source

pub fn rosout_subscription(&self) -> Option<&Subscription<Log>>

Borrow the Subscription to our ROSOut Reader.

Availability depends on Node configuration.

source

pub fn rosout_raw( &self, timestamp: Timestamp, level: LogLevel, log_name: &str, log_msg: &str, source_file: &str, source_function: &str, source_line: u32 )

source

pub fn create_topic( &self, topic_name: &Name, type_name: MessageTypeName, qos: &QosPolicies ) -> CreateResult<Topic>

Creates ROS2 topic and handles necessary conversions from DDS to ROS2

§Arguments
  • domain_participant - DomainParticipant

  • name - Name of the topic

  • type_name - What type the topic holds in string form

  • qos - Quality of Service parameters for the topic (not restricted only to ROS2)

    summary of all rules for topic and service names in ROS 2 (as of Dec 2020)

  • must not be empty

  • may contain alphanumeric characters ([0-9|a-z|A-Z]), underscores (_), or forward slashes (/)

  • may use balanced curly braces ({}) for substitutions

  • may start with a tilde (~), the private namespace substitution character

  • must not start with a numeric character ([0-9])

  • must not end with a forward slash (/)

  • must not contain any number of repeated forward slashes (/)

  • must not contain any number of repeated underscores (_)

  • must separate a tilde (~) from the rest of the name with a forward slash (/), i.e. ~/foo not ~foo

  • must have balanced curly braces ({}) when used, i.e. {sub}/foo but not {sub/foo nor /foo}

source

pub fn create_subscription<D: 'static>( &mut self, topic: &Topic, qos: Option<QosPolicies> ) -> CreateResult<Subscription<D>>

Creates ROS2 Subscriber

§Arguments
  • topic - Reference to topic created with create_ros_topic.
  • qos - Should take QOS and use if it’s compatible with topics QOS. None indicates the use of Topics QOS.
source

pub fn create_publisher<D: Serialize>( &mut self, topic: &Topic, qos: Option<QosPolicies> ) -> CreateResult<Publisher<D>>

Creates ROS2 Publisher

§Arguments
  • topic - Reference to topic created with create_ros_topic.
  • qos - Should take QOS and use it if it’s compatible with topics QOS. None indicates the use of Topics QOS.
source

pub fn create_client<S>( &mut self, service_mapping: ServiceMapping, service_name: &Name, service_type_name: &ServiceTypeName, request_qos: QosPolicies, response_qos: QosPolicies ) -> CreateResult<Client<S>>
where S: Service + 'static, S::Request: Clone,

Creates ROS2 Service Client

§Arguments
  • service_mapping - ServiceMapping to be used
  • service_name -
  • qos-
source

pub fn create_server<S>( &mut self, service_mapping: ServiceMapping, service_name: &Name, service_type_name: &ServiceTypeName, request_qos: QosPolicies, response_qos: QosPolicies ) -> CreateResult<Server<S>>
where S: Service + 'static, S::Request: Clone,

Creates ROS2 Service Server

§Arguments
  • service_mapping - ServiceMapping to be used. See [Self.create_client].
  • service_name -
  • qos-
source

pub fn create_action_client<A>( &mut self, service_mapping: ServiceMapping, action_name: &Name, action_type_name: &ActionTypeName, action_qos: ActionClientQosPolicies ) -> CreateResult<ActionClient<A>>
where A: ActionTypes + 'static,

source

pub fn create_action_server<A>( &mut self, service_mapping: ServiceMapping, action_name: &Name, action_type_name: &ActionTypeName, action_qos: ActionServerQosPolicies ) -> CreateResult<ActionServer<A>>
where A: ActionTypes + 'static,

Trait Implementations§

source§

impl Drop for Node

source§

fn drop(&mut self)

Executes the destructor for this type. Read more

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

§

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

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

source§

fn vzip(self) -> V