rclrs

Struct NodeOptions

Source
pub struct NodeOptions<'a> { /* private fields */ }
Expand description

A set of options for creating a Node.

The builder pattern, implemented through IntoNodeOptions, allows selectively setting some fields, and leaving all others at their default values.

The default values for optional fields are:

  • namespace: "/"
  • use_global_arguments: true
  • arguments: []
  • enable_rosout: true
  • start_parameter_services: true
  • clock_type: ClockType::RosTime
  • clock_qos: QOS_PROFILE_CLOCK

§Example

let executor = Context::default().create_basic_executor();

// Building a node with default options
let node = executor.create_node("foo_node");

// Building a node with a namespace
let node = executor.create_node("bar_node".namespace("/bar"))?;
assert_eq!(node.name(), "bar_node");
assert_eq!(node.namespace(), "/bar");

// Building a node with a namespace and no parameter services
let node = executor.create_node(
    "baz"
    .namespace("qux")
    .start_parameter_services(false)
)?;

// Building node options step-by-step
let mut options = NodeOptions::new("goose");
options = options.namespace("/duck/duck");
options = options.clock_type(ClockType::SteadyTime);

let node = executor.create_node(options)?;
assert_eq!(node.fully_qualified_name(), "/duck/duck/goose");

Implementations§

Source§

impl<'a> NodeOptions<'a>

Source

pub fn new(name: &'a str) -> NodeOptions<'a>

Creates a builder for a node with the given name.

See the Node docs for general information on node names.

§Rules for valid node names

The rules for a valid node name are checked by the rmw_validate_node_name() function. They are:

  • Must contain only the a-z, A-Z, 0-9, and _ characters
  • Must not be empty and not be longer than RMW_NODE_NAME_MAX_NAME_LENGTH
  • Must not start with a number

Note that node name validation is delayed until Executor::create_node.

§Example
let executor = Context::default().create_basic_executor();
// This is a valid node name
assert!(executor.create_node(NodeOptions::new("my_node")).is_ok());
// This is another valid node name (although not a good one)
assert!(executor.create_node(NodeOptions::new("_______")).is_ok());
// This is an invalid node name
assert!(matches!(
    executor.create_node(NodeOptions::new("röböt")).unwrap_err(),
    RclrsError::RclError { code: RclReturnCode::NodeInvalidName, .. }
));

Trait Implementations§

Source§

impl<'a> IntoNodeOptions<'a> for NodeOptions<'a>

Source§

fn into_node_options(self) -> NodeOptions<'a>

Conver the object into NodeOptions with default settings.
Source§

fn namespace(self, namespace: &'a str) -> NodeOptions<'a>

Sets the node namespace. Read more
Source§

fn use_global_arguments(self, enable: bool) -> NodeOptions<'a>

Enables or disables using global arguments. Read more
Source§

fn arguments<Args: IntoIterator>(self, arguments: Args) -> NodeOptions<'a>
where Args::Item: ToString,

Sets node-specific command line arguments. Read more
Source§

fn enable_rosout(self, enable: bool) -> NodeOptions<'a>

Enables or disables logging to rosout. Read more
Source§

fn start_parameter_services(self, start: bool) -> NodeOptions<'a>

Enables or disables parameter services. Read more
Source§

fn clock_type(self, clock_type: ClockType) -> NodeOptions<'a>

Sets the node’s clock type.
Source§

fn clock_qos(self, clock_qos: QoSProfile) -> NodeOptions<'a>

Sets the QoSProfile for the clock subscription.

Auto Trait Implementations§

§

impl<'a> Freeze for NodeOptions<'a>

§

impl<'a> RefUnwindSafe for NodeOptions<'a>

§

impl<'a> Send for NodeOptions<'a>

§

impl<'a> Sync for NodeOptions<'a>

§

impl<'a> Unpin for NodeOptions<'a>

§

impl<'a> UnwindSafe for NodeOptions<'a>

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.