Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/sensor/vpRealSense2.h>
Public Member Functions | |
vpRealSense2 () | |
virtual | ~vpRealSense2 () |
void | acquire (vpImage< unsigned char > &grey, double *ts=nullptr) |
void | acquire (vpImage< vpRGBa > &color, double *ts=nullptr) |
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=nullptr, double *ts=nullptr) |
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=nullptr) |
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=nullptr, rs2::align *const align_to=nullptr, double *ts=nullptr) |
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=nullptr) |
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=nullptr, rs2::align *const align_to=nullptr, double *ts=nullptr) |
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=nullptr) |
void | close () |
vpCameraParameters | getCameraParameters (const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const |
float | getDepthScale () |
rs2_intrinsics | getIntrinsics (const rs2_stream &stream, int index=-1) const |
float | getInvalidDepthValue () const |
float | getMaxZ () const |
rs2::pipeline & | getPipeline () |
rs2::pipeline_profile & | getPipelineProfile () |
std::string | getProductLine () |
std::string | getSensorInfo () |
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) |
Related Functions | |
(Note that these are not member functions.) | |
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 311 of file vpRealSense2.h.
BEGIN_VISP_NAMESPACE vpRealSense2::vpRealSense2 | ( | ) |
Default constructor.
Definition at line 74 of file vpRealSense2.cpp.
|
virtual |
Default destructor that stops the streaming.
Definition at line 83 of file vpRealSense2.cpp.
References close().
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 = nullptr |
||
) |
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_infrared1 | : First infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Second infrared image (if supported by the device) buffer or nullptr if not wanted. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or nullptr if not wanted. |
Definition at line 516 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::PointXYZ >::Ptr & | pointcloud, | ||
unsigned char *const | data_infrared = nullptr , |
||
rs2::align *const | align_to = nullptr , |
||
double * | ts = nullptr |
||
) |
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. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or nullptr if not wanted. |
Definition at line 494 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 = nullptr |
||
) |
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_infrared1 | : First infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Second infrared image (if supported by the device) buffer or nullptr if not wanted. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or nullptr if not wanted. |
Definition at line 601 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 = nullptr , |
||
rs2::align *const | align_to = nullptr , |
||
double * | ts = nullptr |
||
) |
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. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or nullptr if not wanted. |
Definition at line 579 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_infrared, | ||
rs2::align *const | align_to = nullptr , |
||
double * | ts = nullptr |
||
) |
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. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Image timestamp or nullptr if not wanted. |
Definition at line 125 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 = nullptr |
||
) |
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_infrared1 | : First infrared image buffer or nullptr if not wanted. |
data_infrared2 | : Second infrared image buffer (if supported by the device) or nullptr if not wanted. |
align_to | : Align to a reference stream or nullptr if not wanted. Only depth and color streams can be aligned. |
ts | : Data timestamp or nullptr 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 194 of file vpRealSense2.cpp.
References getNativeFrameData(), getPointcloud(), and m_pipe.
void vpRealSense2::acquire | ( | vpImage< unsigned char > & | grey, |
double * | ts = nullptr |
||
) |
Acquire greyscale image from RealSense device.
grey | : Greyscale image. |
ts | : Image timestamp or nullptr if not wanted. |
Definition at line 90 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 nullptr if not wanted. |
Definition at line 105 of file vpRealSense2.cpp.
References getColorFrame(), 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 664 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 distortion parameters or not. |
index | : Index of camera in T265 device, 1: Left 2. Right. Otherwise: -1(default) |
Definition at line 681 of file vpRealSense2.cpp.
References vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpCameraParameters::initProjWithKannalaBrandtDistortion(), m_pipelineProfile, vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, and vpCameraParameters::ProjWithKannalaBrandtDistortion.
Definition at line 734 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 763 of file vpRealSense2.cpp.
References m_depthScale, and m_init.
|
protected |
Definition at line 788 of file vpRealSense2.cpp.
References vpImageConvert::BGRToGrey(), vpImage< Type >::bitmap, vpException::fatalError, vpImage< Type >::resize(), vpImageConvert::RGBaToGrey(), and vpImageConvert::RGBToGrey().
Referenced by acquire().
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 728 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 372 of file vpRealSense2.h.
|
inline |
Get the maximum Z value (used to discard bad reconstructed depth for pointcloud).
Definition at line 376 of file vpRealSense2.h.
|
protected |
Definition at line 812 of file vpRealSense2.cpp.
Referenced by acquire().
|
inline |
Get a reference to rs2::pipeline
.
Definition at line 383 of file vpRealSense2.h.
|
inline |
Get a reference to rs2::pipeline_profile
.
Definition at line 386 of file vpRealSense2.h.
|
protected |
Definition at line 961 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, and m_max_Z.
|
protected |
Definition at line 894 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, m_max_Z, m_pointcloud, and m_points.
|
protected |
Definition at line 842 of file vpRealSense2.cpp.
References vpException::fatalError, m_depthScale, m_invalidDepthValue, and m_max_Z.
Referenced by acquire().
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 1427 of file vpRealSense2.cpp.
References m_product_line.
std::string vpRealSense2::getSensorInfo | ( | ) |
Alias for the &operator<< operator. Return sensor information such as:
Definition at line 1464 of file vpRealSense2.cpp.
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 1152 of file vpRealSense2.cpp.
References m_pipelineProfile.
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 1396 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 = rs2::config() | ) |
Open access to the RealSense device and start the streaming.
Definition at line 1363 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 402 of file vpRealSense2.h.
|
inline |
Set the maximum Z value (used to discard bad reconstructed depth for pointcloud).
Definition at line 406 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 1594 of file vpRealSense2.cpp.
|
related |
Return information from the sensor.
os | : Input stream. |
rs | : RealSense object. |
The following example shows how to use this method.
Definition at line 1594 of file vpRealSense2.cpp.
|
protected |
Definition at line 409 of file vpRealSense2.h.
Referenced by getDepthScale(), getPointcloud(), and open().
|
protected |
Definition at line 420 of file vpRealSense2.h.
Referenced by close(), getDepthScale(), and open().
|
protected |
Definition at line 410 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 411 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 412 of file vpRealSense2.h.
|
protected |
Definition at line 413 of file vpRealSense2.h.
Referenced by getCameraParameters(), getIntrinsics(), getTransformation(), and open().
|
protected |
Definition at line 414 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 415 of file vpRealSense2.h.
Referenced by getPointcloud().
|
protected |
Definition at line 416 of file vpRealSense2.h.
|
protected |
Definition at line 419 of file vpRealSense2.h.
Referenced by getProductLine(), and open().
|
protected |
Definition at line 417 of file vpRealSense2.h.
|
protected |
Definition at line 418 of file vpRealSense2.h.