Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpRealSense2 Class Reference

#include <visp3/sensor/vpRealSense2.h>

Public Member Functions

 vpRealSense2 ()
 
virtual ~vpRealSense2 ()
 
void acquire (vpImage< unsigned char > &grey)
 
void acquire (vpImage< vpRGBa > &color)
 
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)
 
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)
 
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)
 
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)
 
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)
 
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)
 
void close ()
 
vpCameraParameters getCameraParameters (const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
 
float getDepthScale ()
 
rs2_intrinsics getIntrinsics (const rs2_stream &stream) const
 
float getInvalidDepthValue () const
 
float getMaxZ () const
 
rs2::pipeline & getPipeline ()
 
rs2::pipeline_profile & getPipelineProfile ()
 
vpHomogeneousMatrix getTransformation (const rs2_stream &from, const rs2_stream &to) const
 
void open (const rs2::config &cfg=rs2::config())
 
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
 

Friends

VISP_EXPORT 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 (build 2.8.3):
  • Intel® RealSense™ Camera D400-Series (not tested)
  • Intel® RealSense™ Developer Kit SR300 (vpRealSense2 is ok)

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.
project(sample)
cmake_minimum_required(VERSION 2.6)
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;
}

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 <visp3/sensor/vpRealSense2.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
int main()
{
rs.open();
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZRGB>);
rs.acquire(NULL, NULL, NULL, 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(NULL, NULL, NULL, 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:

#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, NULL, NULL, Ii.bitmap);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Ii, false))
break;
}
return 0;
}

This 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, NULL, NULL, &align_to);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Id, false))
break;
}
return 0;
}

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

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;
}
Note
This class has been tested with the Intel RealSense SR300 (Firmware: 3.21.0.0) using librealsense (API version: 2.8.3). Refer to the librealsense2 documentation or API how to for additional information.
Examples:
getRealSense2Info.cpp, grabRealSense2.cpp, servoFrankaIBVS.cpp, servoFrankaPBVS.cpp, testRealSense2_D435.cpp, testRealSense2_D435_align.cpp, testRealSense2_D435_opencv.cpp, testRealSense2_D435_pcl.cpp, testRealSense2_SR300.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live.cpp, tutorial-franka-acquire-calib-data.cpp, tutorial-grabber-realsense.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd-realsense.cpp, and tutorial-pose-from-points-live.cpp.

Definition at line 282 of file vpRealSense2.h.

Constructor & Destructor Documentation

◆ vpRealSense2()

vpRealSense2::vpRealSense2 ( )

Default constructor.

Definition at line 72 of file vpRealSense2.cpp.

◆ ~vpRealSense2()

vpRealSense2::~vpRealSense2 ( )
virtual

Default destructor that stops the streaming.

See also
stop()

Definition at line 82 of file vpRealSense2.cpp.

References close().

Member Function Documentation

◆ acquire() [1/8]

◆ acquire() [2/8]

void vpRealSense2::acquire ( vpImage< vpRGBa > &  color)

Acquire color image from RealSense device.

Parameters
color: Color image.

Definition at line 99 of file vpRealSense2.cpp.

References getColorFrame(), and m_pipe.

◆ acquire() [3/8]

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 
)

Acquire data from RealSense device.

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

Definition at line 115 of file vpRealSense2.cpp.

References acquire().

◆ acquire() [4/8]

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 
)

Acquire data from RealSense device.

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

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, NULL, NULL, Ii1.bitmap, Ii2.bitmap, NULL);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Ii1, false) || vpDisplay::getClick(Ii2, false))
break;
}
return 0;
}

Definition at line 178 of file vpRealSense2.cpp.

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

◆ acquire() [5/8]

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 
)

Acquire data from RealSense device.

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

Definition at line 232 of file vpRealSense2.cpp.

References acquire().

◆ acquire() [6/8]

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 
)

Acquire data from RealSense device.

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

Definition at line 253 of file vpRealSense2.cpp.

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

◆ acquire() [7/8]

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 
)

Acquire data from RealSense device.

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

Definition at line 311 of file vpRealSense2.cpp.

References acquire().

◆ acquire() [8/8]

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 
)

Acquire data from RealSense device.

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

Definition at line 332 of file vpRealSense2.cpp.

References getNativeFrameData(), getPointcloud(), 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 391 of file vpRealSense2.cpp.

References m_pipe.

Referenced by ~vpRealSense2().

◆ getCameraParameters()

◆ 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, and tutorial-apriltag-detector-live-rgbd-realsense.cpp.

Definition at line 462 of file vpRealSense2.cpp.

References m_depthScale.

◆ getGreyFrame()

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

◆ getIntrinsics()

rs2_intrinsics vpRealSense2::getIntrinsics ( const rs2_stream &  stream) 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.
See also
getCameraParameters()
Examples:
grabRealSense2.cpp.

Definition at line 430 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 326 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 330 of file vpRealSense2.h.

◆ getNativeFrameData()

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

Definition at line 488 of file vpRealSense2.cpp.

Referenced by acquire().

◆ getPipeline()

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

Get a reference to rs2::pipeline.

Examples:
testRealSense2_D435_opencv.cpp, and testRealSense2_SR300.cpp.

Definition at line 333 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 336 of file vpRealSense2.h.

◆ getPointcloud() [1/3]

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

Definition at line 518 of file vpRealSense2.cpp.

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

Referenced by acquire().

◆ getPointcloud() [2/3]

void vpRealSense2::getPointcloud ( const rs2::depth_frame &  depth_frame,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud 
)
protected

◆ getPointcloud() [3/3]

void vpRealSense2::getPointcloud ( const rs2::depth_frame &  depth_frame,
const rs2::frame &  color_frame,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud 
)
protected

Definition at line 637 of file vpRealSense2.cpp.

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

◆ getTransformation()

vpHomogeneousMatrix vpRealSense2::getTransformation ( const rs2_stream &  from,
const rs2_stream &  to 
) 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.
Examples:
grabRealSense2.cpp, testRealSense2_SR300.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, and tutorial-mb-generic-tracker-rgbd-realsense.cpp.

Definition at line 817 of file vpRealSense2.cpp.

References m_pipelineProfile.

◆ open()

◆ 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 347 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 351 of file vpRealSense2.h.

Friends And Related Function Documentation

◆ operator<<

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

Member Data Documentation

◆ m_depthScale

float vpRealSense2::m_depthScale
protected

Definition at line 354 of file vpRealSense2.h.

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

◆ m_invalidDepthValue

float vpRealSense2::m_invalidDepthValue
protected

Definition at line 355 of file vpRealSense2.h.

Referenced by getPointcloud().

◆ m_max_Z

float vpRealSense2::m_max_Z
protected

Definition at line 356 of file vpRealSense2.h.

Referenced by getPointcloud().

◆ m_pipe

rs2::pipeline vpRealSense2::m_pipe
protected

Definition at line 357 of file vpRealSense2.h.

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

◆ m_pipelineProfile

rs2::pipeline_profile vpRealSense2::m_pipelineProfile
protected

Definition at line 358 of file vpRealSense2.h.

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

◆ m_pointcloud

rs2::pointcloud vpRealSense2::m_pointcloud
protected

Definition at line 359 of file vpRealSense2.h.

Referenced by getPointcloud().

◆ m_points

rs2::points vpRealSense2::m_points
protected

Definition at line 360 of file vpRealSense2.h.

Referenced by getPointcloud().