Struct realsense_rust::config::Config[][src]

pub struct Config { /* fields omitted */ }
Expand description

Type representing the Pipeline configuration.

Implementations

Construct a new configuration.

Enable the stream of kind stream with the provided attributes.

Returns a mutable reference to self, or a configuration error if the underlying FFI call fails.

Arguments

It is not an error if stream and format do not match appropriately, but you may find that the configuration will never resolve if they do not.. E.g. you cannot pass in Rs2StreamKind::Color alongside Rs2Format::Z16. If you’re unsure, pass in Rs2Format::Any and librealsense2 will determine what the most appropriate format is for a given stream.

The index is can be optionally provided. If it is not provided, then librealsense2 will pick the most suitable stream index it can find.

If either width or height (but not both) are zero, librealsense2 will find the most appropriate value to match the non-zero one. E.g. if width is 640 and height is 0, then librealsense2 will return 640x480 images (the closest appropriate format).

Errors

Returns ConfigurationError::CouldNotEnableStream if any internal exceptions occur while making this call. Note that this does not independently check the values passed into each of the provided arguments / attributes. If those are invalid, they will be checked when you call InactivePipeline::start or InactivePipeline::resolve.

Enable all device streams explicitly.

This enables all streams with the default configuration. What this means is that librealsense2 will pick the format, resolution, and framerate. If you want to specify those values yourself, see Config::enable_stream.

Returns a mutable reference to self if it succeeds or a configuration error.

Errors

Returns ConfigurationError::CouldNotEnableAllStreams if this call fails for whatever reason.

Enable device from a serial number.

This is useful if you want to mandate that your configuration is only applied to a device with a specific serial number. The serial can be obtained from the Device method by passing in Rs2CameraInfo::SerialNumber.

Returns a mutable reference to self if it succeeds or a configuration error.

Errors

Returns ConfigurationError::CouldNotEnableDevice if the device could not be enabled.

Enable device from a file path.

Enables a virtual “device” whose observations have been recorded to a file. If loop_playback is true, then the device will continue to stream observations once it has reached the end of the file by continuously looping back to the first observations in the serialized streams.

Returns a mutable reference to self if it succeeds or a configuration error.

Errors

Returns NulError if the provided file path cannot be cleanly represented as a CString. This usually only occurs if you have null characters in the path. Constructing a path using the utilties in Rust’s std::fs are expected to work.

Returns a ConfigurationError::CouldNotEnableDevice if the device cannot be enabled for any reason. e.g. if your file is valid and can be converted into a CString, but is actually a path to a directory, you’ll likely see an error here.

Enable recording data streams to file.

Configuration option for writing / serializing data from the pipeline to a file. This happens independently of any frame delivery once the pipeline has been started. It is an error if you attempt to record to file if you are streaming from a file (see Config::enable_device_from_file).

Returns a mutable reference to self if it succeeds or an error.

Errors

Returns NulError if the provided file path cannot be cleanly represented as a CString. This usually only occurs if you have null characters in the path. Constructing a path using the utilties in Rust’s std::fs are expected to work.

Returns ConfigurationError::CouldNotEnableRecordingToFile if the path is not a valid path to a file or if you are trying to record to a file while streaming from a file.

Disable a specific data stream by stream index.

Returns a mutable reference to self or a configuration error.

Errors

Returns ConfigurationError::CouldNotDisableStream if the stream cannot be disabled.

Disable data stream by stream kind.

This method removes the first stream of the given stream kind.

Returns a mutable reference to self or a configuration error.

Errors

Returns ConfigurationError::CouldNotDisableStream if the stream cannot be disabled.

Disable all device streams explicitly.

This method disables every stream.

Returns a mutable reference to self or a configuration error.

Errors

Returns ConfigurationError::CouldNotDisableAllStreams if the streams cannot be disabled.

Trait Implementations

Formats the value using the given formatter. Read more

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

Executes the destructor for this type. Read more

Auto Trait Implementations

Blanket Implementations

Gets the TypeId of self. Read more

Immutably borrows from an owned value. Read more

Mutably borrows from an owned value. Read more

Performs the conversion.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.

The type returned in the event of a conversion error.

Performs the conversion.