Provides convenience methods relating to devices. More...
#include <rs.hpp>
Public Member Functions | |
void | disable_motion_tracking (void) |
Disables events polling. | |
void | disable_stream (stream stream) |
Disables specific stream. | |
void | enable_motion_tracking (std::function< void(motion_data)> motion_handler, std::function< void(timestamp_data)> timestamp_handler) |
Sets callback for motion module event. | |
void | enable_motion_tracking (std::function< void(motion_data)> motion_handler) |
Sets the callback for motion module event. | |
void | enable_stream (stream stream, int width, int height, format format, int framerate, output_buffer_format output_buffer_type=output_buffer_format::continous) |
Enables specific stream and requests specific properties. | |
void | enable_stream (stream stream, preset preset) |
Enables specific stream and requests properties using preset. | |
float | get_depth_scale () const |
Retrieves mapping between units of depth image and meters. | |
extrinsics | get_extrinsics (stream from_stream, stream to_stream) const |
Retrieves extrinsic transformation between viewpoints of two different streams. | |
const char * | get_firmware_version () const |
Retrieves version of firmware currently installed on device. | |
const void * | get_frame_data (stream stream) const |
Retrieves contents of latest frame on a stream. | |
unsigned long long | get_frame_number (stream stream) const |
Retrieves frame number. | |
double | get_frame_timestamp (stream stream) const |
Retrieves time at which the latest frame on a stream was captured. | |
const char * | get_info (camera_info info) const |
Retrieves camera-specific information such as versions of various components. | |
extrinsics | get_motion_extrinsics_from (stream from_stream) const |
Retrieves extrinsic transformation between viewpoints of specific stream and motion module. | |
motion_intrinsics | get_motion_intrinsics () const |
Retrieves intrinsic camera parameters for motion module. | |
const char * | get_name () const |
Retrieves human-readable device model string. | |
double | get_option (option option) |
Retrieves current value of single option. | |
const char * | get_option_description (option option) |
Retrieves device-specific option description. | |
void | get_option_range (option option, double &min, double &max, double &step) |
Retrieves available range of values of supported option. | |
void | get_option_range (option option, double &min, double &max, double &step, double &def) |
Retrieves available range of values of supported option. | |
void | get_options (const option *options, size_t count, double *values) |
Efficiently retrieves value of arbitrary number of options, using minimal hardware IO. | |
const char * | get_serial () const |
Retrieves unique serial number of device. | |
format | get_stream_format (stream stream) const |
Retrieves pixel format for specific stream. | |
int | get_stream_framerate (stream stream) const |
Retrieves frame rate for specific stream. | |
int | get_stream_height (stream stream) const |
Retrieves height, in pixels, of a specific stream, equivalent to the height field from the stream's intrinsic. | |
intrinsics | get_stream_intrinsics (stream stream) const |
Retrieves intrinsic camera parameters for specific stream. | |
void | get_stream_mode (stream stream, int index, int &width, int &height, format &format, int &framerate) const |
Determines properties of specific streaming mode. | |
int | get_stream_mode_count (stream stream) const |
Determines number of streaming modes available for given stream. | |
int | get_stream_width (stream stream) const |
Retrieves width, in pixels, of a specific stream, equivalent to the width field from the stream's intrinsic. | |
const char * | get_usb_port_id () const |
Retrieves USB port number of device. | |
int | is_motion_tracking_active () |
Checks if data acquisition is active. | |
bool | is_stream_enabled (stream stream) const |
Determines if specific stream is enabled. | |
bool | is_streaming () const |
Determines if device is currently streaming. | |
bool | poll_for_frames () |
Checks if new frames are available, without blocking. | |
void | send_blob_to_device (rs::blob_type type, void *data, int size) |
Sends device-specific data to device. | |
void | set_frame_callback (rs::stream stream, std::function< void(frame)> frame_handler) |
Sets callback for frame arrival event. | |
void | set_option (option option, double value) |
Sets current value of single option. | |
void | set_options (const option *options, size_t count, const double *values) |
Efficiently sets value of arbitrary number of options, using minimal hardware IO. | |
void | start (rs::source source=rs::source::video) |
Begins streaming on all enabled streams for this device. | |
void | stop (rs::source source=rs::source::video) |
Ends streaming on all streams for this device. | |
bool | supports (capabilities capability) const |
Determines device capabilities. | |
bool | supports (camera_info info_param) const |
Determines device capabilities. | |
bool | supports_option (option option) const |
Determines if device allows specific option to be queried and set. | |
void | wait_for_frames () |
Blocks until new frames are available. | |
Private Member Functions | |
device () | |
device (const device &) | |
device & | operator= (const device &) |
~device () |
rs::device::device | ( | ) | [private] |
rs::device::device | ( | const device & | ) | [private] |
rs::device::~device | ( | ) | [private] |
void rs::device::disable_motion_tracking | ( | void | ) | [inline] |
void rs::device::disable_stream | ( | stream | stream | ) | [inline] |
void rs::device::enable_motion_tracking | ( | std::function< void(motion_data)> | motion_handler, |
std::function< void(timestamp_data)> | timestamp_handler | ||
) | [inline] |
Sets callback for motion module event.
The provided callback will be called the instant new motion or timestamp event is available. Note:
The rs_enable_motion_tracking_cpp()
method is responsible for activating the motion module on-board the device. One of the services it provides is to produce shared and high-resolution timestamps for all components that are connected to it. For Depth, IR, Color and Fisheye sensors, librealsense takes care of that and copies the timestamps on the relevant frames.
However, when you have an external device (such as a compass, magnetometer, light sensor, or other) and wish to synchronize it precisely with image and motion streams, you can connect that sensor to a GPIO that is available on some devices. Every time the sensor signals, you get a timestamp callback with a frame number, source ID, and a timestamp. This timestamp callback allows advanced users to synchronize compass events (presumably coming though I2C or some other method) with RealSense data.
[in] | motion_handler | Frame callback to be invoke on every new motion event |
[in] | timestamp_handler | Frame callback to be invoke on every new timestamp event (can be left-out) |
void rs::device::enable_motion_tracking | ( | std::function< void(motion_data)> | motion_handler | ) | [inline] |
Sets the callback for motion module event.
The provided callback will be called the instant new motion event is available.
[in] | motion_handler | Frame callback to be invokes on every new motion event |
void rs::device::enable_stream | ( | stream | stream, |
int | width, | ||
int | height, | ||
format | format, | ||
int | framerate, | ||
output_buffer_format | output_buffer_type = output_buffer_format::continous |
||
) | [inline] |
Enables specific stream and requests specific properties.
[in] | stream | Stream |
[in] | width | Desired width of frame image in pixels, or 0 if any width is acceptable |
[in] | height | Desired height of frame image in pixels, or 0 if any height is acceptable |
[in] | format | Pixel format of frame image, or ANY if any format is acceptable |
[in] | framerate | Number of frames that will be streamed per second, or 0 if any frame rate is acceptable |
[in] | output_buffer_type | output buffer format (continous in memory / native with pitch) |
void rs::device::enable_stream | ( | stream | stream, |
preset | preset | ||
) | [inline] |
float rs::device::get_depth_scale | ( | ) | const [inline] |
extrinsics rs::device::get_extrinsics | ( | stream | from_stream, |
stream | to_stream | ||
) | const [inline] |
const char* rs::device::get_firmware_version | ( | ) | const [inline] |
const void* rs::device::get_frame_data | ( | stream | stream | ) | const [inline] |
unsigned long long rs::device::get_frame_number | ( | stream | stream | ) | const [inline] |
double rs::device::get_frame_timestamp | ( | stream | stream | ) | const [inline] |
const char* rs::device::get_info | ( | camera_info | info | ) | const [inline] |
extrinsics rs::device::get_motion_extrinsics_from | ( | stream | from_stream | ) | const [inline] |
motion_intrinsics rs::device::get_motion_intrinsics | ( | ) | const [inline] |
const char* rs::device::get_name | ( | ) | const [inline] |
double rs::device::get_option | ( | option | option | ) | [inline] |
const char* rs::device::get_option_description | ( | option | option | ) | [inline] |
void rs::device::get_option_range | ( | option | option, |
double & | min, | ||
double & | max, | ||
double & | step | ||
) | [inline] |
Retrieves available range of values of supported option.
[in] | option | Option |
[out] | min | Minimum value that is acceptable for this option |
[out] | max | Maximum value that is acceptable for this option |
[out] | step | Granularity of options that accept discrete values, or zero if the option accepts continuous values |
void rs::device::get_option_range | ( | option | option, |
double & | min, | ||
double & | max, | ||
double & | step, | ||
double & | def | ||
) | [inline] |
Retrieves available range of values of supported option.
[in] | option | Option |
[out] | min | Minimum value that is acceptable for this option |
[out] | max | Maximum value that is acceptable for this option |
[out] | step | Granularity of options that accept discrete values, or zero if the option accepts continuous values |
[out] | def | Default value of the option |
void rs::device::get_options | ( | const option * | options, |
size_t | count, | ||
double * | values | ||
) | [inline] |
const char* rs::device::get_serial | ( | ) | const [inline] |
format rs::device::get_stream_format | ( | stream | stream | ) | const [inline] |
int rs::device::get_stream_framerate | ( | stream | stream | ) | const [inline] |
int rs::device::get_stream_height | ( | stream | stream | ) | const [inline] |
intrinsics rs::device::get_stream_intrinsics | ( | stream | stream | ) | const [inline] |
void rs::device::get_stream_mode | ( | stream | stream, |
int | index, | ||
int & | width, | ||
int & | height, | ||
format & | format, | ||
int & | framerate | ||
) | const [inline] |
Determines properties of specific streaming mode.
[in] | stream | Stream whose mode will be queried |
[in] | index | Zero-based index of streaming mode |
[out] | width | Width of a frame image in pixels |
[out] | height | Height of a frame image in pixels |
[out] | format | Pixel format of a frame image |
[out] | framerate | Number of frames that will be streamed per second |
int rs::device::get_stream_mode_count | ( | stream | stream | ) | const [inline] |
int rs::device::get_stream_width | ( | stream | stream | ) | const [inline] |
const char* rs::device::get_usb_port_id | ( | ) | const [inline] |
int rs::device::is_motion_tracking_active | ( | ) | [inline] |
bool rs::device::is_stream_enabled | ( | stream | stream | ) | const [inline] |
bool rs::device::is_streaming | ( | ) | const [inline] |
bool rs::device::poll_for_frames | ( | ) | [inline] |
void rs::device::send_blob_to_device | ( | rs::blob_type | type, |
void * | data, | ||
int | size | ||
) | [inline] |
void rs::device::set_frame_callback | ( | rs::stream | stream, |
std::function< void(frame)> | frame_handler | ||
) | [inline] |
Sets callback for frame arrival event.
The provided callback will be called the instant new frame of given stream becomes available once callback is set on certain stream type, frames of this type will no longer be available throuhg wait/poll methods (those two approaches are mutually exclusive) while wait/poll methods provide consistent set of syncronized frames at the expense of extra latency, set frame callbacks provides low latency solution with no syncronization
[in] | stream | Stream |
[in] | frame_handler | Frame callback to be invoked on every new frame |
void rs::device::set_option | ( | option | option, |
double | value | ||
) | [inline] |
void rs::device::set_options | ( | const option * | options, |
size_t | count, | ||
const double * | values | ||
) | [inline] |
void rs::device::start | ( | rs::source | source = rs::source::video | ) | [inline] |
void rs::device::stop | ( | rs::source | source = rs::source::video | ) | [inline] |
bool rs::device::supports | ( | capabilities | capability | ) | const [inline] |
bool rs::device::supports | ( | camera_info | info_param | ) | const [inline] |
bool rs::device::supports_option | ( | option | option | ) | const [inline] |
void rs::device::wait_for_frames | ( | ) | [inline] |