Visual Servoing Platform  version 3.6.1 under development (2024-04-26)
vpRealSense2 Class Reference

#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 (vpImage< unsigned char > *left, vpImage< unsigned char > *right, double *ts=nullptr)
 
void acquire (vpImage< unsigned char > *left, vpImage< unsigned char > *right, vpHomogeneousMatrix *cMw, vpColVector *odo_vel, vpColVector *odo_acc, unsigned int *confidence=nullptr, double *ts=nullptr)
 
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=nullptr, double *ts=nullptr)
 
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=nullptr)
 
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)
 

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)
 

Detailed Description

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.

Note
Supported devices for Intel® RealSense™ SDK 2.0:
  • Intel® RealSense™ Camera D400-Series
  • Intel® RealSense™ Developer Kit SR300
  • Intel® RealSense™ Tracking Camera T265 (librealsense2 version > 2.31.0)

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.

Warning
Notice that the usage of this class requires compiler and library support for the ISO C++ 2011 standard. This support is enabled by default in ViSP when supported by the compiler. Hereafter we give an example of a CMakeLists.txt file that allows to build sample-realsense.cpp that uses vpRealSense2 class.
cmake_minimum_required(VERSION 3.5)
project(sample)
find_package(VISP REQUIRED)
include_directories(${VISP_INCLUDE_DIRS})
add_executable(sample-realsense sample-realsense.cpp)
target_link_libraries(sample-realsense ${VISP_LIBRARIES})

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:

#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/sensor/vpRealSense2.h>
int main()
{
rs.open();
vpImage<unsigned char> I(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
#ifdef VISP_HAVE_X11
vpDisplayX d(I);
#elif defined(VISP_HAVE_GDI)
#endif
while (true) {
rs.acquire(I);
if (vpDisplay::getClick(I, false))
break;
}
return 0;
}
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const

If you want to acquire color images, in the previous sample replace:

vpImage<unsigned char> I(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);

by

vpImage<vpRGBa> I(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);

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

#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <visp3/sensor/vpRealSense2.h>
int main()
{
rs.open();
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZRGB>);
rs.acquire(nullptr, nullptr, nullptr, pointcloud);
pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud);
viewer->setBackgroundColor(0, 0, 0);
viewer->initCameraParameters();
viewer->setCameraPosition(0, 0, -0.5, 0, -1, 0);
while (true) {
rs.acquire(nullptr, nullptr, nullptr, pointcloud);
static bool update = false;
if (!update) {
viewer->addPointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
update = true;
} else {
viewer->updatePointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
}
viewer->spinOnce(30);
}
return 0;
}

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:

#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/sensor/vpRealSense2.h>
int main() {
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, 1920, 1080, RS2_FORMAT_RGBA8, 30);
config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
rs.open(config);
vpImage<vpRGBa> Ic(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
vpImage<unsigned char> Ii(rs.getIntrinsics(RS2_STREAM_INFRARED).height,
rs.getIntrinsics(RS2_STREAM_INFRARED).width);
#ifdef VISP_HAVE_X11
vpDisplayX dc(Ic, 0, 0, "Color");
vpDisplayX di(Ii, 100, 100, "Infrared");
#elif defined(VISP_HAVE_GDI)
vpDisplayGDI dc(Ic, 0, 0, "Color");
vpDisplayGDI di(Ii, 100, 100, "Infrared");
#endif
while (true) {
rs.acquire((unsigned char *) Ic.bitmap, nullptr, nullptr, Ii.bitmap);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Ii, false))
break;
}
return 0;
}

This other example shows how to get depth stream aligned on color stream:

#include <visp3/core/vpImageConvert.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/sensor/vpRealSense2.h>
int main() {
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
rs.open(config);
vpImage<vpRGBa> Ic(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
vpImage<uint16_t> Id_raw(rs.getIntrinsics(RS2_STREAM_DEPTH).height, rs.getIntrinsics(RS2_STREAM_DEPTH).width);
vpImage<vpRGBa> Id(rs.getIntrinsics(RS2_STREAM_DEPTH).height, rs.getIntrinsics(RS2_STREAM_DEPTH).width);
#ifdef VISP_HAVE_X11
vpDisplayX dc(Ic, 0, 0, "Color");
vpDisplayX dd(Id, 100, 100, "Depth aligned to color");
#elif defined(VISP_HAVE_GDI)
vpDisplayGDI dc(Ic, 0, 0, "Color");
vpDisplayGDI dd(Id, 100, 100, "Depth aligned to color");
#endif
rs2::align align_to(RS2_STREAM_COLOR);
while (true) {
rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, nullptr, nullptr, &align_to);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Id, false))
break;
}
return 0;
}
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)

References to rs2::pipeline_profile and rs2::pipeline can be retrieved with (rs.open() must be called before):

rs2::pipeline_profile& profile = rs.getPipelineProfile();
rs2::pipeline& pipeline = rs.getPipeline();
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:362
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:359

Information about the sensor can be printed with:

#include <visp3/sensor/vpRealSense2.h>
int main() {
rs.open();
std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
return 0;
}

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.

Note
Additional information can be found in the librealsense wiki.
Examples
getRealSense2Info.cpp, grabRealSense2.cpp, grabRealSense2_T265.cpp, saveRealSenseData.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6MegaposePBVS.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, testRealSense2_D435.cpp, testRealSense2_D435_align.cpp, testRealSense2_D435_opencv.cpp, testRealSense2_D435_pcl.cpp, testRealSense2_SR300.cpp, testRealSense2_T265_images.cpp, testRealSense2_T265_images_odometry.cpp, testRealSense2_T265_images_odometry_async.cpp, testRealSense2_T265_imu.cpp, testRealSense2_T265_odometry.cpp, testRealSense2_T265_undistort.cpp, tutorial-apriltag-detector-live-T265-realsense.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live.cpp, tutorial-grabber-realsense-T265.cpp, tutorial-grabber-realsense.cpp, tutorial-grabber-rgbd-D435-structurecore.cpp, tutorial-hsv-range-tuner.cpp, tutorial-hsv-segmentation-pcl-viewer.cpp, tutorial-hsv-segmentation-pcl.cpp, tutorial-hsv-segmentation.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd-realsense-json.cpp, tutorial-mb-generic-tracker-rgbd-realsense.cpp, tutorial-pose-from-points-live.cpp, and tutorial-pose-from-points-realsense-T265.cpp.

Definition at line 287 of file vpRealSense2.h.

Constructor & Destructor Documentation

◆ vpRealSense2()

vpRealSense2::vpRealSense2 ( )

Default constructor.

Definition at line 71 of file vpRealSense2.cpp.

◆ ~vpRealSense2()

vpRealSense2::~vpRealSense2 ( )
virtual

Default destructor that stops the streaming.

See also
stop()

Definition at line 80 of file vpRealSense2.cpp.

References close().

Member Function Documentation

◆ acquire() [1/7]

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.

Parameters
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 122 of file vpRealSense2.cpp.

References acquire().

◆ acquire() [2/7]

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.

Parameters
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:

#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/sensor/vpRealSense2.h>
int main() {
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
config.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
config.enable_stream(RS2_STREAM_INFRARED, 2, 640, 480, RS2_FORMAT_Y8, 30);
rs.open(config);
vpImage<vpRGBa> Ic(rs.getIntrinsics(RS2_STREAM_COLOR).height, rs.getIntrinsics(RS2_STREAM_COLOR).width);
vpImage<unsigned char> Ii1(rs.getIntrinsics(RS2_STREAM_INFRARED).height,
rs.getIntrinsics(RS2_STREAM_INFRARED).width);
vpImage<unsigned char> Ii2(rs.getIntrinsics(RS2_STREAM_INFRARED).height,
rs.getIntrinsics(RS2_STREAM_INFRARED).width);
#ifdef VISP_HAVE_X11
vpDisplayX dc(Ic, 0, 0, "Color");
vpDisplayX di1(Ii1, 100, 100, "Infrared 1");
vpDisplayX di2(Ii2, 200, 200, "Infrared 2");
#elif defined(VISP_HAVE_GDI)
vpDisplayGDI dc(Ic, 0, 0, "Color");
vpDisplayGDI di1(Ii1, 100, 100, "Infrared 1");
vpDisplayGDI di2(Ii2, 100, 100, "Infrared 2");
#endif
while (true) {
rs.acquire((unsigned char *) Ic.bitmap, nullptr, nullptr, Ii1.bitmap, Ii2.bitmap, nullptr);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Ii1, false) || vpDisplay::getClick(Ii2, false))
break;
}
return 0;
}

Definition at line 186 of file vpRealSense2.cpp.

References getNativeFrameData(), getPointcloud(), and m_pipe.

◆ acquire() [3/7]

◆ acquire() [4/7]

void vpRealSense2::acquire ( vpImage< unsigned char > *  left,
vpImage< unsigned char > *  right,
double *  ts = nullptr 
)

Acquire timestamped greyscale images from T265 RealSense device at 30Hz.

Parameters
left: Left image.
right: Right image.
ts: Data timestamp.

Pass nullptr 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:

rs2::config config;
config.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8);
config.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8);
rs.open(config);
rs.acquire(nullptr, &I_right, nullptr, nullptr);

Definition at line 253 of file vpRealSense2.cpp.

References getNativeFrameData(), m_pipe, and vpImage< Type >::resize().

◆ acquire() [5/7]

void vpRealSense2::acquire ( vpImage< unsigned char > *  left,
vpImage< unsigned char > *  right,
vpHomogeneousMatrix cMw,
vpColVector odo_vel,
vpColVector odo_acc,
unsigned int *  confidence = nullptr,
double *  ts = nullptr 
)

Acquire timestamped greyscale images and odometry data from T265 Realsense device at 30Hz.

Parameters
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 nullptr to one of these parameters if you don't want the corresponding data.

For example if you are only interested in the pose, use:

rs2::config config;
config.enable_stream(RS2_STREAM_POSE, RS2_FORMAT_6DOF);
config.enable_stream(RS2_STREAM_FISHEYE, 1, RS2_FORMAT_Y8);
config.enable_stream(RS2_STREAM_FISHEYE, 2, RS2_FORMAT_Y8);
config.enable_stream(RS2_STREAM_GYRO);
config.enable_stream(RS2_STREAM_ACCEL);
rs.open(config);
rs.acquire(nullptr, nullptr, &cMw, nullptr, nullptr, nullptr, nullptr);
Implementation of an homogeneous matrix and operations on such kind of matrices.

Definition at line 306 of file vpRealSense2.cpp.

References getNativeFrameData(), m_pipe, m_pos, m_quat, vpImage< Type >::resize(), and vpColVector::resize().

◆ acquire() [6/7]

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 = nullptr,
double *  ts = nullptr 
)

Acquire timestamped greyscale images, odometry and raw motion data from T265 Realsense device at 30Hz.

Parameters
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 385 of file vpRealSense2.cpp.

References getNativeFrameData(), m_pipe, m_pos, m_quat, vpImage< Type >::resize(), and vpColVector::resize().

◆ acquire() [7/7]

void vpRealSense2::acquire ( vpImage< vpRGBa > &  color,
double *  ts = nullptr 
)

Acquire color image from RealSense device.

Parameters
color: Color image.
ts: Image timestamp or nullptr if not wanted.

Definition at line 102 of file vpRealSense2.cpp.

References getColorFrame(), and m_pipe.

◆ close()

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.

Examples
testRealSense2_D435.cpp, and testRealSense2_SR300.cpp.

Definition at line 656 of file vpRealSense2.cpp.

References m_init, and m_pipe.

Referenced by open(), and ~vpRealSense2().

◆ getCameraParameters()

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().

Parameters
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)
See also
getIntrinsics()
Examples
grabRealSense2.cpp, servoAfma6AprilTagIBVS.cpp, servoAfma6AprilTagPBVS.cpp, servoAfma6MegaposePBVS.cpp, servoBiclopsPoint2DArtVelocity.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, servoPololuPtuPoint2DJointVelocity.cpp, servoUniversalRobotsIBVS.cpp, servoUniversalRobotsPBVS.cpp, testRealSense2_D435_align.cpp, testRealSense2_D435_opencv.cpp, testRealSense2_SR300.cpp, testRealSense2_T265_undistort.cpp, tutorial-apriltag-detector-live-T265-realsense.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-hsv-segmentation-pcl-viewer.cpp, tutorial-hsv-segmentation-pcl.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-rgbd-realsense-json.cpp, tutorial-mb-generic-tracker-rgbd-realsense.cpp, and tutorial-pose-from-points-realsense-T265.cpp.

Definition at line 673 of file vpRealSense2.cpp.

References vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), vpCameraParameters::initProjWithKannalaBrandtDistortion(), m_pipelineProfile, vpCameraParameters::perspectiveProjWithDistortion, vpCameraParameters::perspectiveProjWithoutDistortion, and vpCameraParameters::ProjWithKannalaBrandtDistortion.

◆ getColorFrame()

void vpRealSense2::getColorFrame ( const rs2::frame &  frame,
vpImage< vpRGBa > &  color 
)
protected

◆ getDepthScale()

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.

Examples
getRealSense2Info.cpp, testRealSense2_D435_align.cpp, testRealSense2_D435_opencv.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-hsv-segmentation-pcl-viewer.cpp, and tutorial-hsv-segmentation-pcl.cpp.

Definition at line 755 of file vpRealSense2.cpp.

References m_depthScale, and m_init.

◆ getGreyFrame()

void vpRealSense2::getGreyFrame ( const rs2::frame &  frame,
vpImage< unsigned char > &  grey 
)
protected

◆ getIMUAcceleration()

void vpRealSense2::getIMUAcceleration ( vpColVector imu_acc,
double *  ts 
)

Get timestamped IMU acceleration from RealSense T265 device at 62.5Hz.

Parameters
imu_acc: IMU 3-dim linear acceleration vector.
ts: Timestamp.
Note
This function should be used with RS2_STREAM_ACCEL stream enabled.
Be aware that IMU frame's X and Z axes are opposite to X and Z axes of pose frame.
rs2::config config;
config.enable_stream(RS2_STREAM_ACCEL);
rs.open(config);
vpColVector imu_acc;
double timestamp;
rs.getIMUAcceleration(&imu_acc, &timestamp);
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
void getIMUAcceleration(vpColVector *imu_acc, double *ts)

Definition at line 1249 of file vpRealSense2.cpp.

References m_pipe, and vpColVector::resize().

◆ getIMUData()

void vpRealSense2::getIMUData ( vpColVector imu_acc,
vpColVector imu_vel,
double *  ts 
)

Get timestamped IMU data from RealSense T265 device.

Parameters
imu_acc: IMU 3-dim linear acceleration vector.
imu_vel: IMU 3-dim angular velocity vector from gyro.
ts: Timestamp.
Note
Be aware that IMU frame's X and Z axes are opposite to X and Z axes of pose frame.
rs2::config config;
config.enable_stream(RS2_STREAM_ACCEL);
config.enable_stream(RS2_STREAM_GYRO);
rs.open(config);
vpColVector imu_acc, imu_vel;
double timestamp;
rs.getIMUVelocity(&imu_acc, &imu_vel, &timestamp);
void getIMUVelocity(vpColVector *imu_vel, double *ts)
Examples
testRealSense2_T265_imu.cpp.

Definition at line 1323 of file vpRealSense2.cpp.

References m_pipe, and vpColVector::resize().

◆ getIMUVelocity()

void vpRealSense2::getIMUVelocity ( vpColVector imu_vel,
double *  ts 
)

Get timestamped IMU angular velocities from RealSense T265 device at 200Hz.

Parameters
imu_vel: IMU 3-dim angular velocity vector from gyro.
ts: Timestamp.
Note
This function should be used with RS2_STREAM_GYRO stream enabled.
Be aware that IMU frame's X and Z axes are opposite to X and Z axes of pose frame.
rs2::config config;
config.enable_stream(RS2_STREAM_GYRO);
rs.open(config);
vpColVector imu_vel;
double timestamp;
rs.getIMUVelocity(&imu_vel, &timestamp);

Definition at line 1286 of file vpRealSense2.cpp.

References m_pipe, and vpColVector::resize().

◆ getIntrinsics()

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().

Parameters
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
See also
getCameraParameters()
Examples
grabRealSense2.cpp, testRealSense2_T265_images.cpp, testRealSense2_T265_images_odometry_async.cpp, and testRealSense2_T265_undistort.cpp.

Definition at line 720 of file vpRealSense2.cpp.

References m_pipelineProfile.

◆ getInvalidDepthValue()

float vpRealSense2::getInvalidDepthValue ( ) const
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 348 of file vpRealSense2.h.

◆ getMaxZ()

float vpRealSense2::getMaxZ ( ) const
inline

Get the maximum Z value (used to discard bad reconstructed depth for pointcloud).

Definition at line 352 of file vpRealSense2.h.

◆ getNativeFrameData()

void vpRealSense2::getNativeFrameData ( const rs2::frame &  frame,
unsigned char *const  data 
)
protected

Definition at line 804 of file vpRealSense2.cpp.

Referenced by acquire().

◆ getOdometryData()

unsigned int vpRealSense2::getOdometryData ( vpHomogeneousMatrix cMw,
vpColVector odo_vel,
vpColVector odo_acc,
double *  ts = nullptr 
)

Get timestamped odometry data from T265 device at 30Hz.

Parameters
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.
Returns
Pose estimation confidence (1: Low, 2: Medium, 3: High).
Examples
testRealSense2_T265_odometry.cpp.

Definition at line 1183 of file vpRealSense2.cpp.

References m_pipe, m_pos, m_quat, and vpColVector::resize().

◆ getPipeline()

rs2::pipeline& vpRealSense2::getPipeline ( )
inline

Get a reference to rs2::pipeline.

Examples
testRealSense2_D435_opencv.cpp, and testRealSense2_SR300.cpp.

Definition at line 359 of file vpRealSense2.h.

◆ getPipelineProfile()

rs2::pipeline_profile& vpRealSense2::getPipelineProfile ( )
inline

Get a reference to rs2::pipeline_profile.

Examples
testRealSense2_D435_opencv.cpp, and testRealSense2_SR300.cpp.

Definition at line 362 of file vpRealSense2.h.

◆ getPointcloud()

void vpRealSense2::getPointcloud ( const rs2::depth_frame &  depth_frame,
std::vector< vpColVector > &  pointcloud 
)
protected

Definition at line 834 of file vpRealSense2.cpp.

References vpException::fatalError, m_depthScale, m_invalidDepthValue, and m_max_Z.

Referenced by acquire().

◆ getProductLine()

std::string vpRealSense2::getProductLine ( )

Get the product line of the device being used. This function need librealsense > 2.31.0. Otherwise it returns "unknown".

Examples
getRealSense2Info.cpp, grabRealSense2.cpp, grabRealSense2_T265.cpp, testRealSense2_T265_images.cpp, testRealSense2_T265_images_odometry.cpp, testRealSense2_T265_imu.cpp, testRealSense2_T265_odometry.cpp, and testRealSense2_T265_undistort.cpp.

Definition at line 1419 of file vpRealSense2.cpp.

References m_product_line.

◆ getSensorInfo()

std::string vpRealSense2::getSensorInfo ( )

Alias for the &operator<< operator. Return sensor information such as:

  • device info
  • supported options
  • stream profiles
  • intrinsics / extrinsics
  • [...]

Definition at line 1456 of file vpRealSense2.cpp.

◆ getTransformation()

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().

Parameters
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)
Examples
grabRealSense2.cpp, testRealSense2_SR300.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-rgbd-realsense-json.cpp, and tutorial-mb-generic-tracker-rgbd-realsense.cpp.

Definition at line 1144 of file vpRealSense2.cpp.

References m_pipelineProfile.

◆ open() [1/2]

bool vpRealSense2::open ( const rs2::config &  cfg,
std::function< void(rs2::frame)> &  callback 
)

Open access to the RealSense device and start the streaming.

Parameters
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 1388 of file vpRealSense2.cpp.

References close(), m_depthScale, m_init, m_pipe, m_pipelineProfile, and m_product_line.

◆ open() [2/2]

bool vpRealSense2::open ( const rs2::config &  cfg = rs2::config())

◆ setInvalidDepthValue()

void vpRealSense2::setInvalidDepthValue ( float  value)
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 378 of file vpRealSense2.h.

◆ setMaxZ()

void vpRealSense2::setMaxZ ( const float  maxZ)
inline

Set the maximum Z value (used to discard bad reconstructed depth for pointcloud).

Definition at line 382 of file vpRealSense2.h.

Friends And Related Function Documentation

◆ operator<< [1/2]

std::ostream & operator<< ( std::ostream &  os,
const vpRealSense2 rs 
)
friend

Return information from the sensor.

Parameters
os: Input stream.
rs: RealSense object.

The following example shows how to use this method.

#include <visp3/sensor/vpRealSense2.h>
int main()
{
rs.open();
std::cout << "RealSense sensor information:\n" << rs << std::endl;
return 0;
}

Definition at line 1582 of file vpRealSense2.cpp.

◆ operator<<() [2/2]

std::ostream & operator<< ( std::ostream &  os,
const vpRealSense2 rs 
)
related

Return information from the sensor.

Parameters
os: Input stream.
rs: RealSense object.

The following example shows how to use this method.

#include <visp3/sensor/vpRealSense2.h>
int main()
{
rs.open();
std::cout << "RealSense sensor information:\n" << rs << std::endl;
return 0;
}

Definition at line 1582 of file vpRealSense2.cpp.

Member Data Documentation

◆ m_depthScale

float vpRealSense2::m_depthScale
protected

Definition at line 385 of file vpRealSense2.h.

Referenced by getDepthScale(), getPointcloud(), and open().

◆ m_init

bool vpRealSense2::m_init
protected

Definition at line 396 of file vpRealSense2.h.

Referenced by close(), getDepthScale(), and open().

◆ m_invalidDepthValue

float vpRealSense2::m_invalidDepthValue
protected

Definition at line 386 of file vpRealSense2.h.

Referenced by getPointcloud().

◆ m_max_Z

float vpRealSense2::m_max_Z
protected

Definition at line 387 of file vpRealSense2.h.

Referenced by getPointcloud().

◆ m_pipe

rs2::pipeline vpRealSense2::m_pipe
protected

◆ m_pipelineProfile

rs2::pipeline_profile vpRealSense2::m_pipelineProfile
protected

Definition at line 389 of file vpRealSense2.h.

Referenced by getCameraParameters(), getIntrinsics(), getTransformation(), and open().

◆ m_pointcloud

rs2::pointcloud vpRealSense2::m_pointcloud
protected

Definition at line 390 of file vpRealSense2.h.

◆ m_points

rs2::points vpRealSense2::m_points
protected

Definition at line 391 of file vpRealSense2.h.

◆ m_pos

vpTranslationVector vpRealSense2::m_pos
protected

Definition at line 392 of file vpRealSense2.h.

Referenced by acquire(), and getOdometryData().

◆ m_product_line

std::string vpRealSense2::m_product_line
protected

Definition at line 395 of file vpRealSense2.h.

Referenced by getProductLine(), and open().

◆ m_quat

vpQuaternionVector vpRealSense2::m_quat
protected

Definition at line 393 of file vpRealSense2.h.

Referenced by acquire(), and getOdometryData().

◆ m_rot

vpRotationMatrix vpRealSense2::m_rot
protected

Definition at line 394 of file vpRealSense2.h.