Visual Servoing Platform
version 3.5.0 under development (2022-02-15)
|
#include <visp3/sensor/vpRealSense2.h>
Public Member Functions | |
vpRealSense2 () | |
virtual | ~vpRealSense2 () |
void | acquire (vpImage< unsigned char > &grey, double *ts=NULL) |
void | acquire (vpImage< vpRGBa > &color, double *ts=NULL) |
void | acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, unsigned char *const data_infrared, rs2::align *const align_to=NULL, double *ts=NULL) |
void | acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, unsigned char *const data_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL) |
void | acquire (vpImage< unsigned char > *left, vpImage< unsigned char > *right, double *ts=NULL) |
void | acquire (vpImage< unsigned char > *left, vpImage< unsigned char > *right, vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence=NULL, double *ts=NULL) |
void | acquire (vpImage< unsigned char > *left, vpImage< unsigned char > *right, vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, vpColVector *imu_vel, vpColVector *imu_acc, unsigned int *tracker_confidence=NULL, double *ts=NULL) |
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=NULL, rs2::align *const align_to=NULL, double *ts=NULL) |
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_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL) |
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=NULL, rs2::align *const align_to=NULL, double *ts=NULL) |
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_infrared1, unsigned char *const data_infrared2, rs2::align *const align_to, double *ts=NULL) |
void | close () |
vpCameraParameters | getCameraParameters (const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const |
float | getDepthScale () |
void | getIMUAcceleration (vpColVector *imu_acc, double *ts) |
void | getIMUData (vpColVector *imu_vel, vpColVector *imu_acc, double *ts) |
void | getIMUVelocity (vpColVector *imu_vel, double *ts) |
rs2_intrinsics | getIntrinsics (const rs2_stream &stream, int index=-1) const |
float | getInvalidDepthValue () const |
float | getMaxZ () const |
unsigned int | getOdometryData (vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, double *ts=NULL) |
rs2::pipeline & | getPipeline () |
rs2::pipeline_profile & | getPipelineProfile () |
std::string | getProductLine () |
vpHomogeneousMatrix | getTransformation (const rs2_stream &from, const rs2_stream &to, int from_index=-1) const |
bool | open (const rs2::config &cfg=rs2::config()) |
bool | open (const rs2::config &cfg, std::function< void(rs2::frame)> &callback) |
void | setInvalidDepthValue (float value) |
void | setMaxZ (const float maxZ) |
Protected Member Functions | |
void | getColorFrame (const rs2::frame &frame, vpImage< vpRGBa > &color) |
void | getGreyFrame (const rs2::frame &frame, vpImage< unsigned char > &grey) |
void | getNativeFrameData (const rs2::frame &frame, unsigned char *const data) |
void | getPointcloud (const rs2::depth_frame &depth_frame, std::vector< vpColVector > &pointcloud) |
void | getPointcloud (const rs2::depth_frame &depth_frame, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud) |
void | getPointcloud (const rs2::depth_frame &depth_frame, const rs2::frame &color_frame, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud) |
Protected Attributes | |
float | m_depthScale |
float | m_invalidDepthValue |
float | m_max_Z |
rs2::pipeline | m_pipe |
rs2::pipeline_profile | m_pipelineProfile |
rs2::pointcloud | m_pointcloud |
rs2::points | m_points |
vpTranslationVector | m_pos |
vpQuaternionVector | m_quat |
vpRotationMatrix | m_rot |
std::string | m_product_line |
bool | m_init |
Friends | |
VISP_EXPORT std::ostream & | operator<< (std::ostream &os, const vpRealSense2 &rs) |
This class provides a lightweight wrapper over the Intel librealsense2 library https://github.com/IntelRealSense/librealsense. It allows to capture data from the Intel RealSense cameras.
The usage of vpRealSense2 class is enabled when librealsense2 3rd party is successfully installed.
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, refer to the librealsense2 rs2::config
documentation. The following code allows to capture the color stream in 1920x1080 at 30 Hz:
This other example shows how to get depth stream aligned on color stream:
References to rs2::pipeline_profile
and rs2::pipeline
can be retrieved with (rs.open() must be called before
):
Information about the sensor can be printed with:
It is also possible to use several RealSense sensors at the same time. In that case, you need to create a vpRealSense2 object for each device and use vpRealSense2::enable_device(const std::string &serial_number) to select the device explicitly by its serial number. An example is provided in tutorial-grabber-multiple-realsense.cpp.
Definition at line 286 of file vpRealSense2.h.
vpRealSense2::vpRealSense2 | ( | ) |
Default constructor.
Definition at line 72 of file vpRealSense2.cpp.
|
virtual |
Default destructor that stops the streaming.
Definition at line 82 of file vpRealSense2.cpp.
References close().
void vpRealSense2::acquire | ( | vpImage< unsigned char > & | grey, |
double * | ts = NULL |
||
) |
Acquire greyscale image from RealSense device.
grey | : Greyscale image. |
ts | : Image timestamp or NULL if not wanted. |
Definition at line 89 of file vpRealSense2.cpp.
References getGreyFrame(), and m_pipe.
Referenced by acquire().
Acquire color image from RealSense device.
color | : Color image. |
ts | : Image timestamp or NULL if not wanted. |
Definition at line 104 of file vpRealSense2.cpp.
References getColorFrame(), and m_pipe.
void vpRealSense2::acquire | ( | unsigned char *const | data_image, |
unsigned char *const | data_depth, | ||
std::vector< vpColVector > *const | data_pointCloud, | ||
unsigned char *const | data_infrared, | ||
rs2::align *const | align_to = NULL , |
||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
data_infrared | : Infrared image buffer or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Image timestamp or NULL if not wanted. |
Definition at line 124 of file vpRealSense2.cpp.
References acquire().
void vpRealSense2::acquire | ( | unsigned char *const | data_image, |
unsigned char *const | data_depth, | ||
std::vector< vpColVector > *const | data_pointCloud, | ||
unsigned char *const | data_infrared1, | ||
unsigned char *const | data_infrared2, | ||
rs2::align *const | align_to, | ||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
data_infrared1 | : First infrared image buffer or NULL if not wanted. |
data_infrared2 | : Second infrared image buffer (if supported by the device) or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or NULL if not wanted. |
The following code shows how to use this function to get color, infrared 1 and infrared 2 frames acquired by a D435 device:
Definition at line 188 of file vpRealSense2.cpp.
References getNativeFrameData(), getPointcloud(), and m_pipe.
void vpRealSense2::acquire | ( | vpImage< unsigned char > * | left, |
vpImage< unsigned char > * | right, | ||
double * | ts = NULL |
||
) |
Acquire timestamped greyscale images from T265 RealSense device at 30Hz.
left | : Left image. |
right | : Right image. |
ts | : Data timestamp. |
Pass NULL to one of these parameters if you don't want the corresponding data.
For example if you are only interested in the right fisheye image, use:
Definition at line 255 of file vpRealSense2.cpp.
References getNativeFrameData(), m_pipe, and vpImage< Type >::resize().
void vpRealSense2::acquire | ( | vpImage< unsigned char > * | left, |
vpImage< unsigned char > * | right, | ||
vpHomogeneousMatrix * | cMw, | ||
vpColVector * | odo_vel, | ||
vpColVector * | odo_acc, | ||
unsigned int * | confidence = NULL , |
||
double * | ts = NULL |
||
) |
Acquire timestamped greyscale images and odometry data from T265 Realsense device at 30Hz.
left | : Left image. |
right | : Right image. |
cMw | : Pointer to pose from visual odometry. |
odo_vel | : Pointer to 6-dim linear and angular velocities vector from visual odometry. |
odo_acc | : Pointer to 6-dim linear and angular acceleration vector from visual odometry. |
confidence | : Pose estimation confidence (1: Low, 2: Medium, 3: High). |
ts | : Data timestamp. |
Pass NULL to one of these parameters if you don't want the corresponding data.
For example if you are only interested in the pose, use:
Definition at line 308 of file vpRealSense2.cpp.
References getNativeFrameData(), m_pipe, m_pos, m_quat, vpColVector::resize(), and vpImage< Type >::resize().
void vpRealSense2::acquire | ( | vpImage< unsigned char > * | left, |
vpImage< unsigned char > * | right, | ||
vpHomogeneousMatrix * | cMw, | ||
vpColVector * | odo_vel, | ||
vpColVector * | odo_acc, | ||
vpColVector * | imu_vel, | ||
vpColVector * | imu_acc, | ||
unsigned int * | confidence = NULL , |
||
double * | ts = NULL |
||
) |
Acquire timestamped greyscale images, odometry and raw motion data from T265 Realsense device at 30Hz.
left | : Left image. |
right | : Right image. |
cMw | : Pointer to pose from visual odometry. |
odo_vel | : Pointer to 6-dim linear and angular velocities vector from visual odometry. |
odo_acc | : Pointer to 6-dim linear and angular acceleration vector from visual odometry. |
imu_vel | : Pointer to IMU 3-dim angular velocity vector from gyro. |
imu_acc | : Pointer to IMU 3-dim linear acceleration vector. |
confidence | : Pose estimation confidence (1: Low, 2: Medium, 3: High). |
ts | : Data timestamp. |
Definition at line 387 of file vpRealSense2.cpp.
References getNativeFrameData(), m_pipe, m_pos, m_quat, vpColVector::resize(), and vpImage< Type >::resize().
void vpRealSense2::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 = NULL , |
||
rs2::align *const | align_to = NULL , |
||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
pointcloud | : Point cloud (in PCL format and without texture information) pointer or NULL if not wanted. |
data_infrared | : Infrared image buffer or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or NULL if not wanted. |
Definition at line 488 of file vpRealSense2.cpp.
References acquire().
void vpRealSense2::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_infrared1, | ||
unsigned char *const | data_infrared2, | ||
rs2::align *const | align_to, | ||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
pointcloud | : Point cloud (in PCL format and without texture information) pointer or NULL if not wanted. |
data_infrared1 | : First infrared image buffer or NULL if not wanted. |
data_infrared2 | : Second infrared image (if supported by the device) buffer or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or NULL if not wanted. |
Definition at line 510 of file vpRealSense2.cpp.
References getNativeFrameData(), getPointcloud(), and m_pipe.
void vpRealSense2::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 = NULL , |
||
rs2::align *const | align_to = NULL , |
||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
pointcloud | : Point cloud (in PCL format and with texture information) pointer or NULL if not wanted. |
data_infrared | : Infrared image buffer or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or NULL if not wanted. |
Definition at line 573 of file vpRealSense2.cpp.
References acquire().
void vpRealSense2::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_infrared1, | ||
unsigned char *const | data_infrared2, | ||
rs2::align *const | align_to, | ||
double * | ts = NULL |
||
) |
Acquire data from RealSense device.
data_image | : Color image buffer or NULL if not wanted. |
data_depth | : Depth image buffer or NULL if not wanted. |
data_pointCloud | : Point cloud vector pointer or NULL if not wanted. |
pointcloud | : Point cloud (in PCL format and with texture information) pointer or NULL if not wanted. |
data_infrared1 | : First infrared image buffer or NULL if not wanted. |
data_infrared2 | : Second infrared image (if supported by the device) buffer or NULL if not wanted. |
align_to | : Align to a reference stream or NULL if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or NULL if not wanted. |
Definition at line 595 of file vpRealSense2.cpp.
References getNativeFrameData(), getPointcloud(), and m_pipe.
void vpRealSense2::close | ( | ) |
librealsense documentation:
Stop the pipeline streaming. The pipeline stops delivering samples to the attached computer vision modules and processing blocks, stops the device streaming and releases the device resources used by the pipeline. It is the application's responsibility to release any frame reference it owns. The method takes effect only after
start()
was called, otherwise an exception is raised.
Definition at line 658 of file vpRealSense2.cpp.
References m_init, and m_pipe.
Referenced by open(), and ~vpRealSense2().
vpCameraParameters vpRealSense2::getCameraParameters | ( | const rs2_stream & | stream, |
vpCameraParameters::vpCameraParametersProjType | type = vpCameraParameters::perspectiveProjWithDistortion , |
||
int | index = -1 |
||
) | const |
Return the camera parameters corresponding to a specific stream. This function has to be called after open().
stream | : Stream for which camera intrinsic parameters are returned. |
type | : Indicates if the model should include distorsion parameters or not. |
index | : Index of camera in T265 device, 1: Left 2. Right. Otherwise: -1(default) |
Definition at line 675 of file vpRealSense2.cpp.
References vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpCameraParameters::initProjWithKannalaBrandtDistortion(), m_pipelineProfile, vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, and vpCameraParameters::ProjWithKannalaBrandtDistortion.
Definition at line 732 of file vpRealSense2.cpp.
References vpImageConvert::BGRToRGBa(), vpImage< Type >::bitmap, vpException::fatalError, vpImage< Type >::resize(), and vpImageConvert::RGBToRGBa().
Referenced by acquire().
float vpRealSense2::getDepthScale | ( | ) |
Get depth scale value used to convert all the uint16_t values contained in a depth frame into a distance in meter.
Definition at line 758 of file vpRealSense2.cpp.
References m_depthScale, and m_init.
|
protected |
Definition at line 783 of file vpRealSense2.cpp.
References vpImageConvert::BGRToGrey(), vpImage< Type >::bitmap, vpException::fatalError, vpImage< Type >::resize(), vpImageConvert::RGBaToGrey(), and vpImageConvert::RGBToGrey().
Referenced by acquire().
void vpRealSense2::getIMUAcceleration | ( | vpColVector * | imu_acc, |
double * | ts | ||
) |
Get timestamped IMU acceleration from RealSense T265 device at 62.5Hz.
imu_acc | : IMU 3-dim linear acceleration vector. |
ts | : Timestamp. |
Definition at line 1242 of file vpRealSense2.cpp.
References m_pipe, and vpColVector::resize().
void vpRealSense2::getIMUData | ( | vpColVector * | imu_acc, |
vpColVector * | imu_vel, | ||
double * | ts | ||
) |
Get timestamped IMU data from RealSense T265 device.
imu_acc | : IMU 3-dim linear acceleration vector. |
imu_vel | : IMU 3-dim angular velocity vector from gyro. |
ts | : Timestamp. |
Definition at line 1318 of file vpRealSense2.cpp.
References m_pipe, and vpColVector::resize().
void vpRealSense2::getIMUVelocity | ( | vpColVector * | imu_vel, |
double * | ts | ||
) |
Get timestamped IMU angular velocities from RealSense T265 device at 200Hz.
imu_vel | : IMU 3-dim angular velocity vector from gyro. |
ts | : Timestamp. |
Definition at line 1280 of file vpRealSense2.cpp.
References m_pipe, and vpColVector::resize().
rs2_intrinsics vpRealSense2::getIntrinsics | ( | const rs2_stream & | stream, |
int | index = -1 |
||
) | const |
Get intrinsic parameters corresponding to the stream. This function has to be called after open().
stream | : Stream for which the camera intrinsic parameters are returned. |
index | : Index of the stream. Default: -1. In case of T265 camera: Left Fisheye: 1, Right Fisheye: 2 |
Definition at line 726 of file vpRealSense2.cpp.
References m_pipelineProfile.
|
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 344 of file vpRealSense2.h.
|
inline |
Get the maximum Z value (used to discard bad reconstructed depth for pointcloud).
Definition at line 348 of file vpRealSense2.h.
|
protected |
Definition at line 804 of file vpRealSense2.cpp.
Referenced by acquire().
unsigned int vpRealSense2::getOdometryData | ( | vpHomogeneousMatrix * | cMw, |
vpColVector * | odo_vel, | ||
vpColVector * | odo_acc, | ||
double * | ts = NULL |
||
) |
Get timestamped odometry data from T265 device at 30Hz.
cMw | : Pose given by visual odometry. |
odo_vel | : Pointer to 6-dim linear and angular velocities vector from visual odometry. |
odo_acc | : Pointer to 6-dim linear and angular acceleration vector from visual odometry. |
ts | : Timestamp. |
Definition at line 1174 of file vpRealSense2.cpp.
References m_pipe, m_pos, m_quat, and vpColVector::resize().
|
inline |
Get a reference to rs2::pipeline
.
Definition at line 355 of file vpRealSense2.h.
|
inline |
Get a reference to rs2::pipeline_profile
.
Definition at line 358 of file vpRealSense2.h.
|
protected |
Definition at line 834 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, and m_max_Z.
Referenced by acquire().
|
protected |
Definition at line 887 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, m_max_Z, m_pointcloud, and m_points.
|
protected |
Definition at line 953 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, and m_max_Z.
std::string vpRealSense2::getProductLine | ( | ) |
Get the product line of the device being used. This function need librealsense > 2.31.0. Otherwise it returns "unknown".
Definition at line 1414 of file vpRealSense2.cpp.
References m_init, and m_product_line.
vpHomogeneousMatrix vpRealSense2::getTransformation | ( | const rs2_stream & | from, |
const rs2_stream & | to, | ||
int | from_index = -1 |
||
) | const |
Get the extrinsic transformation from one stream to another. This function has to be called after open().
from,to | : Streams for which the camera extrinsic parameters are returned. |
from_index | : Index of the stream from which we will calculate the transformation, 1: From left to right, 2: From right to left. Otherwise: -1(default) |
Definition at line 1134 of file vpRealSense2.cpp.
References m_pipelineProfile.
bool vpRealSense2::open | ( | const rs2::config & | cfg = rs2::config() | ) |
Open access to the RealSense device and start the streaming.
Definition at line 1352 of file vpRealSense2.cpp.
References close(), m_depthScale, m_init, m_pipe, m_pipelineProfile, and m_product_line.
bool vpRealSense2::open | ( | const rs2::config & | cfg, |
std::function< void(rs2::frame)> & | callback | ||
) |
Open access to the RealSense device and start the streaming.
cfg | : A rs2::config with requested filters on the pipeline configuration. By default no filters are applied. |
callback | : Stream callback, can be any callable object accepting rs2::frame. The callback is invoked immediately once a frame is ready. |
Definition at line 1384 of file vpRealSense2.cpp.
References close(), m_depthScale, m_init, m_pipe, m_pipelineProfile, and m_product_line.
|
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 372 of file vpRealSense2.h.
|
inline |
Set the maximum Z value (used to discard bad reconstructed depth for pointcloud).
Definition at line 376 of file vpRealSense2.h.
|
friend |
Return information from the sensor.
os | : Input stream. |
rs | : RealSense object. |
The following example shows how to use this method.
Definition at line 1556 of file vpRealSense2.cpp.
|
protected |
Definition at line 379 of file vpRealSense2.h.
Referenced by getDepthScale(), getPointcloud(), and open().
|
protected |
Definition at line 390 of file vpRealSense2.h.
Referenced by close(), getDepthScale(), getProductLine(), and open().
|
protected |
Definition at line 380 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 381 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 382 of file vpRealSense2.h.
Referenced by acquire(), close(), getIMUAcceleration(), getIMUData(), getIMUVelocity(), getOdometryData(), and open().
|
protected |
Definition at line 383 of file vpRealSense2.h.
Referenced by getCameraParameters(), getIntrinsics(), getTransformation(), and open().
|
protected |
Definition at line 384 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 385 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 386 of file vpRealSense2.h.
Referenced by acquire(), and getOdometryData().
|
protected |
Definition at line 389 of file vpRealSense2.h.
Referenced by getProductLine(), and open().
|
protected |
Definition at line 387 of file vpRealSense2.h.
Referenced by acquire(), and getOdometryData().
|
protected |
Definition at line 388 of file vpRealSense2.h.