Visual Servoing Platform
version 3.6.1 under development (2024-10-10)
|
#include <visp3/sensor/vpRealSense.h>
Classes | |
struct | vpRsStreamParams |
Public Member Functions | |
vpRealSense () | |
virtual | ~vpRealSense () |
void | acquire (std::vector< vpColVector > &pointcloud) |
void | acquire (pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | acquire (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud) |
void | acquire (vpImage< unsigned char > &grey) |
void | acquire (vpImage< unsigned char > &grey, std::vector< vpColVector > &pointcloud) |
void | acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, std::vector< vpColVector > &pointcloud) |
void | acquire (vpImage< unsigned char > &grey, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud) |
void | acquire (vpImage< vpRGBa > &color) |
void | acquire (vpImage< vpRGBa > &color, std::vector< vpColVector > &pointcloud) |
void | acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, std::vector< vpColVector > &pointcloud) |
void | acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=nullptr, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2) |
void | acquire (vpImage< vpRGBa > &color, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud) |
void | acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=nullptr, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2) |
void | acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=nullptr, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2) |
void | close () |
vpCameraParameters | getCameraParameters (const rs::stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const |
rs::device * | getHandler () const |
rs::extrinsics | getExtrinsics (const rs::stream &from, const rs::stream &to) const |
rs::intrinsics | getIntrinsics (const rs::stream &stream) const |
float | getInvalidDepthValue () const |
int | getNumDevices () const |
std::string | getSerialNumber () const |
vpHomogeneousMatrix | getTransformation (const rs::stream &from, const rs::stream &to) const |
void | open () |
void | setDeviceBySerialNumber (const std::string &serial_no) |
void | setEnableStream (const rs::stream &stream, bool status) |
void | setInvalidDepthValue (float value) |
void | setStreamSettings (const rs::stream &stream, const rs::preset &preset) |
void | setStreamSettings (const rs::stream &stream, const vpRsStreamParams ¶ms) |
Protected Member Functions | |
void | initStream () |
Protected Attributes | |
rs::context | m_context |
rs::device * | m_device |
int | m_num_devices |
std::string | m_serial_no |
std::map< rs::stream, rs::intrinsics > | m_intrinsics |
float | m_max_Z |
std::map< rs::stream, bool > | m_enableStreams |
std::map< rs::stream, bool > | m_useStreamPresets |
std::map< rs::stream, rs::preset > | m_streamPresets |
std::map< rs::stream, vpRsStreamParams > | m_streamParams |
float | m_invalidDepthValue |
Friends | |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpRealSense &rs) |
Related Functions | |
(Note that these are not member functions.) | |
std::ostream & | operator<< (std::ostream &os, const vpRealSense &rs) |
This class is a wrapper over the Intel librealsense library https://github.com/IntelRealSense/librealsense. It allows to capture data from the Intel RealSense cameras.
The usage of vpRealSense class is enabled when librealsense 3rd party is successfully installed. Installation instructions are provided following https://github.com/IntelRealSense/librealsense#installation-guide.
Moreover, if Point Cloud Library (PCL) 3rd party is installed we also propose interfaces to retrieve point cloud as pcl::PointCloud<pcl::PointXYZ> or pcl::PointCloud<pcl::PointXYZRGB> data structures.
To acquire images from the RealSense color camera and convert them into grey level images, a good starting is to use the following code that corresponds to the content of sample-realsense.cpp:
If you want to acquire color images, in the previous sample replace:
by
If you are interested in the point cloud and if ViSP is build with PCL support, you can start from the following example where we use PCL library to visualize the point cloud:
If you want to change the default stream parameters, you can use setEnableStream()
to enable only the desired stream and setStreamSettings()
to set the stream settings. The following code allows to capture the color stream in 1920x1080 also with the infrared stream:
This example shows how to get depth stream aligned on color stream:
This is how you get intrinsics for non native stream (the native stream has to be enabled!):
Useful information can be retrieved using getHandler()
:
Camera parameters can be set in the following manner:
Definition at line 360 of file vpRealSense.h.
BEGIN_VISP_NAMESPACE vpRealSense::vpRealSense | ( | ) |
|
virtual |
Default destructor that stops the streaming.
Definition at line 61 of file vpRealSense.cpp.
References close().
void vpRealSense::acquire | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud | ) |
Acquire data from RealSense device.
pointcloud | : Point cloud data information. |
Definition at line 691 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pointcloud | ) |
Acquire data from RealSense device.
pointcloud | : Point cloud data with texture information. |
Definition at line 710 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | std::vector< vpColVector > & | pointcloud | ) |
Acquire data from RealSense device.
pointcloud | : Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point. |
Definition at line 428 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | unsigned char *const | data_image, |
unsigned char *const | data_depth, | ||
std::vector< vpColVector > *const | data_pointCloud, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud, | ||
unsigned char *const | data_infrared, | ||
unsigned char *const | data_infrared2 = nullptr , |
||
const rs::stream & | stream_color = rs::stream::color , |
||
const rs::stream & | stream_depth = rs::stream::depth , |
||
const rs::stream & | stream_infrared = rs::stream::infrared , |
||
const rs::stream & | stream_infrared2 = rs::stream::infrared2 |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or nullptr if not wanted. |
data_depth | : Depth image buffer or nullptr if not wanted. |
data_pointCloud | : Point cloud vector pointer or nullptr if not wanted. |
pointcloud | : Point cloud (in PCL format and without texture information) pointer or nullptr if not wanted. |
data_infrared | : Infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Infrared (for the second IR camera if available) image buffer or nullptr if not wanted. |
stream_color | : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). |
stream_depth | : Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2). |
stream_infrared | : Type of infrared stream (only rs::stream::infrared should be possible). |
stream_infrared2 | : Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera. |
Definition at line 918 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | unsigned char *const | data_image, |
unsigned char *const | data_depth, | ||
std::vector< vpColVector > *const | data_pointCloud, | ||
pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pointcloud, | ||
unsigned char *const | data_infrared, | ||
unsigned char *const | data_infrared2 = nullptr , |
||
const rs::stream & | stream_color = rs::stream::color , |
||
const rs::stream & | stream_depth = rs::stream::depth , |
||
const rs::stream & | stream_infrared = rs::stream::infrared , |
||
const rs::stream & | stream_infrared2 = rs::stream::infrared2 |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or nullptr if not wanted. |
data_depth | : Depth image buffer or nullptr if not wanted. |
data_pointCloud | : Point cloud vector pointer or nullptr if not wanted. |
pointcloud | : Point cloud (in PCL format and with texture information) pointer or nullptr if not wanted. |
data_infrared | : Infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Infrared (for the second IR camera if available) image buffer or nullptr if not wanted. |
stream_color | : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). |
stream_depth | : Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2). |
stream_infrared | : Type of infrared stream (only rs::stream::infrared should be possible). |
stream_infrared2 | : Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera. |
Definition at line 978 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | unsigned char *const | data_image, |
unsigned char *const | data_depth, | ||
std::vector< vpColVector > *const | data_pointCloud, | ||
unsigned char *const | data_infrared, | ||
unsigned char *const | data_infrared2 = nullptr , |
||
const rs::stream & | stream_color = rs::stream::color , |
||
const rs::stream & | stream_depth = rs::stream::depth , |
||
const rs::stream & | stream_infrared = rs::stream::infrared , |
||
const rs::stream & | stream_infrared2 = rs::stream::infrared2 |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or nullptr if not wanted. |
data_depth | : Depth image buffer or nullptr if not wanted. |
data_pointCloud | : Point cloud vector pointer or nullptr if not wanted. |
data_infrared | : Infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Infrared (for the second IR camera if available) image buffer or nullptr if not wanted. |
stream_color | : Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth). |
stream_depth | : Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2). |
stream_infrared | : Type of infrared stream (only rs::stream::infrared should be possible). |
stream_infrared2 | : Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera. |
Definition at line 572 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey | ) |
Acquire data from RealSense device.
grey | : Grey level image. |
Definition at line 382 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey, |
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
grey | : Grey level image. |
pointcloud | : Point cloud data information. |
Definition at line 730 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey, |
std::vector< vpColVector > & | pointcloud | ||
) |
Acquire data from RealSense device.
grey | : Grey level image. |
pointcloud | : Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point. |
Definition at line 404 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
grey | : Grey level image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data information. |
Definition at line 810 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
grey | : Grey level image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data with texture information. |
Definition at line 874 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< unsigned char > & | grey, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
std::vector< vpColVector > & | pointcloud | ||
) |
Acquire data from RealSense device.
grey | : Grey level image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point. |
Definition at line 505 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
Acquire data from RealSense device.
color | : Color image. |
Definition at line 447 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, and open().
void vpRealSense::acquire | ( | vpImage< vpRGBa > & | color, |
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
color | : Color image. |
pointcloud | : Point cloud data information. |
Definition at line 753 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< vpRGBa > & | color, |
std::vector< vpColVector > & | pointcloud | ||
) |
Acquire data from RealSense device.
color | : Color image. |
pointcloud | : Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point. |
Definition at line 537 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< vpRGBa > & | color, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
pcl::PointCloud< pcl::PointXYZ >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
color | : Color image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data information. |
Definition at line 778 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< vpRGBa > & | color, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | pointcloud | ||
) |
Acquire data from RealSense device.
color | : Color image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data with texture information. |
Definition at line 842 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::acquire | ( | vpImage< vpRGBa > & | color, |
vpImage< uint16_t > & | infrared, | ||
vpImage< uint16_t > & | depth, | ||
std::vector< vpColVector > & | pointcloud | ||
) |
Acquire data from RealSense device.
color | : Color image. |
infrared | : Infrared image. |
depth | : Depth image. |
pointcloud | : Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point. |
Definition at line 471 of file vpRealSense.cpp.
References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().
void vpRealSense::close | ( | ) |
Stop device streaming.
Definition at line 243 of file vpRealSense.cpp.
References m_device.
Referenced by ~vpRealSense().
vpCameraParameters vpRealSense::getCameraParameters | ( | const rs::stream & | stream, |
vpCameraParameters::vpCameraParametersProjType | type = vpCameraParameters::perspectiveProjWithDistortion |
||
) | const |
Return camera parameters corresponding to a specific stream. This function has to be called after open().
stream | : color, depth, infrared or infrared2 stream for which camera intrinsic parameters are returned. |
type | : Indicate if the model should include distortion paramater or not. |
Definition at line 293 of file vpRealSense.cpp.
References getIntrinsics(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), and vpCameraParameters::perspectiveProjWithDistortion.
rs::extrinsics vpRealSense::getExtrinsics | ( | const rs::stream & | from, |
const rs::stream & | to | ||
) | const |
Get extrinsic transformation from one stream to an other. This function has to be called after open().
from,to | : color, depth, infrared or infrared2 stream between which camera extrinsic parameters are returned. |
Definition at line 336 of file vpRealSense.cpp.
References vpException::fatalError, and m_device.
Referenced by getTransformation().
|
inline |
Get access to device handler.
Definition at line 422 of file vpRealSense.h.
rs::intrinsics vpRealSense::getIntrinsics | ( | const rs::stream & | stream | ) | const |
Get intrinsic parameters corresponding to the stream. This function has to be called after open().
stream | : color, depth, infrared or infrared2 stream for which camera intrinsic parameters are returned. |
Definition at line 319 of file vpRealSense.cpp.
References vpException::fatalError, and m_device.
Referenced by getCameraParameters().
|
inline |
Get the value used when the pixel value (u, v) in the depth map is invalid for the point cloud. For instance, the Point Cloud Library (PCL) uses NAN values for points where the depth is invalid.
Definition at line 430 of file vpRealSense.h.
|
inline |
Get number of devices that are detected.
Definition at line 433 of file vpRealSense.h.
|
inline |
Get device serial number.
Definition at line 436 of file vpRealSense.h.
vpHomogeneousMatrix vpRealSense::getTransformation | ( | const rs::stream & | from, |
const rs::stream & | to | ||
) | const |
Get extrinsic transformation from one stream to an other. This function has to be called after open().
from,to | : color, depth, infrared or infrared2 stream between which camera extrinsic parameters are returned. |
Definition at line 364 of file vpRealSense.cpp.
References getExtrinsics().
|
protected |
Definition at line 63 of file vpRealSense.cpp.
References m_enableStreams, m_streamParams, m_streamPresets, and m_useStreamPresets.
Referenced by vpRealSense().
void vpRealSense::open | ( | ) |
Open access to the RealSense device and start the streaming.
Definition at line 96 of file vpRealSense.cpp.
References vpException::fatalError, m_context, m_device, m_enableStreams, m_intrinsics, m_num_devices, m_serial_no, m_streamParams, m_streamPresets, and m_useStreamPresets.
Referenced by acquire().
void vpRealSense::setDeviceBySerialNumber | ( | const std::string & | serial_no | ) |
Set active RealSence device using its serial number.
serial_no | : Device serial number. |
Definition at line 272 of file vpRealSense.cpp.
References vpException::fatalError, m_num_devices, and m_serial_no.
void vpRealSense::setEnableStream | ( | const rs::stream & | stream, |
bool | status | ||
) |
Enable or disable a stream.
stream | : Stream type (color / depth / infrared). |
status | : Stream status. |
Definition at line 684 of file vpRealSense.cpp.
References m_enableStreams.
|
inline |
Set the value used when the pixel value (u, v) in the depth map is invalid for the point cloud. For instance, the Point Cloud Library (PCL) uses NAN values for points where the depth is invalid.
Definition at line 468 of file vpRealSense.h.
void vpRealSense::setStreamSettings | ( | const rs::stream & | stream, |
const rs::preset & | preset | ||
) |
Set stream settings.
stream | : Stream type (color / depth / infrared). |
preset | : Preset to use. |
Definition at line 614 of file vpRealSense.cpp.
References m_streamPresets, and m_useStreamPresets.
void vpRealSense::setStreamSettings | ( | const rs::stream & | stream, |
const vpRsStreamParams & | params | ||
) |
Set stream settings.
stream | : Stream type (color / depth / infrared). |
params | : Stream parameters to use. |
Definition at line 651 of file vpRealSense.cpp.
References m_streamParams, and m_useStreamPresets.
|
friend |
Return information from sensor.
os | : Input stream. |
rs | : RealSense interface. |
The following example shows how to use this method.
Definition at line 1046 of file vpRealSense.cpp.
|
related |
Return information from sensor.
os | : Input stream. |
rs | : RealSense interface. |
The following example shows how to use this method.
Definition at line 1046 of file vpRealSense.cpp.
|
protected |
Definition at line 474 of file vpRealSense.h.
Referenced by open().
|
protected |
Definition at line 475 of file vpRealSense.h.
Referenced by acquire(), close(), getExtrinsics(), getIntrinsics(), and open().
|
protected |
Definition at line 480 of file vpRealSense.h.
Referenced by initStream(), open(), and setEnableStream().
|
protected |
Definition at line 478 of file vpRealSense.h.
|
protected |
Definition at line 484 of file vpRealSense.h.
Referenced by acquire().
|
protected |
|
protected |
Definition at line 476 of file vpRealSense.h.
Referenced by open(), and setDeviceBySerialNumber().
|
protected |
Definition at line 477 of file vpRealSense.h.
Referenced by open(), and setDeviceBySerialNumber().
|
protected |
Definition at line 483 of file vpRealSense.h.
Referenced by initStream(), open(), and setStreamSettings().
|
protected |
Definition at line 482 of file vpRealSense.h.
Referenced by initStream(), open(), and setStreamSettings().
|
protected |
Definition at line 481 of file vpRealSense.h.
Referenced by initStream(), open(), and setStreamSettings().