Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpRealSense Class Reference

#include <visp3/sensor/vpRealSense.h>

Classes

struct  vpRsStreamParams
 

Public Member Functions

 vpRealSense ()
 
virtual ~vpRealSense ()
 
void acquire (std::vector< vpColVector > &pointcloud)
 
void acquire (pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void acquire (pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud)
 
void acquire (vpImage< unsigned char > &grey)
 
void acquire (vpImage< unsigned char > &grey, std::vector< vpColVector > &pointcloud)
 
void acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, std::vector< vpColVector > &pointcloud)
 
void acquire (vpImage< unsigned char > &grey, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void acquire (vpImage< unsigned char > &grey, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud)
 
void acquire (vpImage< vpRGBa > &color)
 
void acquire (vpImage< vpRGBa > &color, std::vector< vpColVector > &pointcloud)
 
void acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, std::vector< vpColVector > &pointcloud)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=NULL, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2)
 
void acquire (vpImage< vpRGBa > &color, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud)
 
void acquire (vpImage< vpRGBa > &color, vpImage< uint16_t > &infrared, vpImage< uint16_t > &depth, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &pointcloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=NULL, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2)
 
void acquire (unsigned char *const data_image, unsigned char *const data_depth, std::vector< vpColVector > *const data_pointCloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &pointcloud, unsigned char *const data_infrared, unsigned char *const data_infrared2=NULL, const rs::stream &stream_color=rs::stream::color, const rs::stream &stream_depth=rs::stream::depth, const rs::stream &stream_infrared=rs::stream::infrared, const rs::stream &stream_infrared2=rs::stream::infrared2)
 
void close ()
 
vpCameraParameters getCameraParameters (const rs::stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
 
rs::device * getHandler () const
 
rs::extrinsics getExtrinsics (const rs::stream &from, const rs::stream &to) const
 
rs::intrinsics getIntrinsics (const rs::stream &stream) const
 
float getInvalidDepthValue () const
 
int getNumDevices () const
 
std::string getSerialNumber () const
 
vpHomogeneousMatrix getTransformation (const rs::stream &from, const rs::stream &to) const
 
void open ()
 
void setDeviceBySerialNumber (const std::string &serial_no)
 
void setEnableStream (const rs::stream &stream, const bool status)
 
void setInvalidDepthValue (const float value)
 
void setStreamSettings (const rs::stream &stream, const rs::preset &preset)
 
void setStreamSettings (const rs::stream &stream, const vpRsStreamParams &params)
 

Protected Member Functions

void initStream ()
 

Protected Attributes

rs::context m_context
 
rs::device * m_device
 
int m_num_devices
 
std::string m_serial_no
 
std::map< rs::stream,
rs::intrinsics > 
m_intrinsics
 
float m_max_Z
 
std::map< rs::stream, bool > m_enableStreams
 
std::map< rs::stream, bool > m_useStreamPresets
 
std::map< rs::stream, rs::preset > m_streamPresets
 
std::map< rs::stream,
vpRsStreamParams
m_streamParams
 
float m_invalidDepthValue
 

Friends

VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpRealSense &rs)
 

Detailed Description

This class is a wrapper over the Intel librealsense library https://github.com/IntelRealSense/librealsense. It allows to capture data from the Intel RealSense F200, SR300 and R200 cameras.

The usage of vpRealSense class is enabled when librealsense 3rd party is successfully installed. Installation instructions are provided following https://github.com/IntelRealSense/librealsense#installation-guide.

Moreover, if Point Cloud Library (PCL) 3rd party is installed we also propose interfaces to retrieve point cloud as pcl::PointCloud<pcl::PointXYZ> or pcl::PointCloud<pcl::PointXYZRGB> data structures.

Warning
Notice that the usage of this class requires compiler and library support for the ISO C++ 2011 standard. This support must be enabled with the -std=c++11 compiler option. Hereafter we give an example of a CMakeLists.txt file that allows to build sample-realsense.cpp that uses vpRealSense class.
project(sample)
cmake_minimum_required(VERSION 2.6)
find_package(VISP REQUIRED)
include_directories(${VISP_INCLUDE_DIRS})
include(CheckCXXCompilerFlag)
check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
endif()
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/sensor/vpRealSense.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
int main()
{
rs.open();
vpImage<unsigned char> I(rs.getIntrinsics(rs::stream::color).height, rs.getIntrinsics(rs::stream::color).width);
#ifdef VISP_HAVE_X11
vpDisplayX d(I);
#elif defined(VISP_HAVE_GDI)
#endif
while (1) {
rs.acquire(I);
if (vpDisplay::getClick(I, false))
break;
}
}

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

vpImage<unsigned char> I(rs.getIntrinsics(rs::stream::color).height, rs.getIntrinsics(rs::stream::color).width);

by

vpImage<vpRGBa> I(rs.getIntrinsics(rs::stream::color).height, rs.getIntrinsics(rs::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/vpRealSense.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
int main()
{
rs.open();
std::cout << rs << std::endl;
pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZRGB>);
rs.acquire(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->addCoordinateSystem (1.0);
viewer->initCameraParameters ();
viewer->setCameraPosition(0,0,-0.5, 0,-1,0);
while (1) {
rs.acquire(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 (100);
}
}

If you want to change the default stream parameters, you can use setEnableStream() to enable only the desired stream and setStreamSettings() to set the stream settings. The following code allows to capture the color stream in 1920x1080 also with the infrared stream:

#include <visp3/sensor/vpRealSense.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
int main() {
rs.setEnableStream(rs::stream::color, true);
rs.setEnableStream(rs::stream::depth, false);
rs.setEnableStream(rs::stream::infrared, true);
rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30));
rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 30));
rs.open();
vpImage<vpRGBa> Ic(rs.getIntrinsics(rs::stream::color).height, rs.getIntrinsics(rs::stream::color).width);
vpImage<unsigned char> Ii(rs.getIntrinsics(rs::stream::infrared).height, rs.getIntrinsics(rs::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 (1) {
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/sensor/vpRealSense.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
int main() {
rs.setEnableStream(rs::stream::color, true);
rs.setEnableStream(rs::stream::depth, true);
rs.setEnableStream(rs::stream::infrared, false);
rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30));
rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30));
rs.open();
vpImage<vpRGBa> Ic(rs.getIntrinsics(rs::stream::color).height, rs.getIntrinsics(rs::stream::color).width);
vpImage<uint16_t> Id_raw(rs.getIntrinsics(rs::stream::depth).height, rs.getIntrinsics(rs::stream::depth).width);
vpImage<vpRGBa> Id(rs.getIntrinsics(rs::stream::depth).height, rs.getIntrinsics(rs::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
while (1) {
rs.acquire((unsigned char *) Ic.bitmap, (unsigned char *) Id_raw.bitmap, NULL, NULL, NULL, rs::stream::color, rs::stream::depth_aligned_to_color);
if (vpDisplay::getClick(Ic, false) || vpDisplay::getClick(Id, false))
break;
}
return 0;
}

This is how you get intrinsics for non native stream (the native stream has to be enabled!):

#include <visp3/sensor/vpRealSense.h>
int main() {
rs.setEnableStream(rs::stream::color, true);
rs.setEnableStream(rs::stream::depth, true);
rs.setEnableStream(rs::stream::infrared, false);
rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30));
rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30));
rs.open();
rs::device * dev = rs.getHandler();
rs::intrinsics depth_aligned_intrinsic = dev->get_stream_intrinsics(rs::stream::depth_aligned_to_color);
std::cout << "Intrinsics [fx, fy, ppx, ppy]: " << depth_aligned_intrinsic.fx << " ; " << depth_aligned_intrinsic.fy
<< " ; " << depth_aligned_intrinsic.ppx << " ; " << depth_aligned_intrinsic.ppy << std::endl;
return 0;
}

Useful information can be retrieved using getHandler():

#include <visp3/sensor/vpRealSense.h>
#include <librealsense/rs.hpp>
int main() {
rs.open();
rs::device *device = rs.getHandler();
std::cout << "Stream width: " << device->get_stream_width(rs::stream::color) << std::endl;
std::cout << "Stream height: " << device->get_stream_height(rs::stream::color) << std::endl;
std::cout << "Stream format: " << device->get_stream_format(rs::stream::color) << std::endl;
std::cout << "Stream framerate: " << device->get_stream_framerate(rs::stream::color) << std::endl;
std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl;
std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *) device, nullptr) << std::endl;
std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
return 0;
}
Note
This class has been tested with the Intel RealSense SR300. The following streams are enabled by default:
  • Color stream with preset: best quality
  • Depth stream with preset: best quality
  • Infrared stream with preset: best quality
  • Infrared2 if supported with preset: best quality
Examples:
grabRealSense.cpp, and testRealSense.cpp.

Definition at line 308 of file vpRealSense.h.

Constructor & Destructor Documentation

vpRealSense::vpRealSense ( )

Default constructor.

Definition at line 51 of file vpRealSense.cpp.

References initStream().

vpRealSense::~vpRealSense ( )
virtual

Default destructor that stops the streaming.

See Also
stop()

Definition at line 62 of file vpRealSense.cpp.

References close().

Member Function Documentation

void vpRealSense::acquire ( std::vector< vpColVector > &  pointcloud)

Acquire data from RealSense device.

Parameters
pointcloud: Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point.
Examples:
grabRealSense.cpp, and testRealSense.cpp.

Definition at line 386 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud)

Acquire data from RealSense device.

Parameters
pointcloud: Point cloud data information.

Definition at line 625 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud)

Acquire data from RealSense device.

Parameters
pointcloud: Point cloud data with texture information.

Definition at line 644 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey)

Acquire data from RealSense device.

Parameters
grey: Grey level image.

Definition at line 344 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey,
std::vector< vpColVector > &  pointcloud 
)

Acquire data from RealSense device.

Parameters
grey: Grey level image.
pointcloud: Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point.

Definition at line 364 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
std::vector< vpColVector > &  pointcloud 
)

Acquire data from RealSense device.

Parameters
grey: Grey level image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point.

Definition at line 458 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
grey: Grey level image.
pointcloud: Point cloud data information.

Definition at line 664 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
grey: Grey level image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data information.

Definition at line 743 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< unsigned char > &  grey,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
grey: Grey level image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data with texture information.

Definition at line 805 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

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

Acquire data from RealSense device.

Parameters
color: Color image.

Definition at line 405 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, and open().

void vpRealSense::acquire ( vpImage< vpRGBa > &  color,
std::vector< vpColVector > &  pointcloud 
)

Acquire data from RealSense device.

Parameters
color: Color image.
pointcloud: Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point.

Definition at line 487 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< vpRGBa > &  color,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
std::vector< vpColVector > &  pointcloud 
)

Acquire data from RealSense device.

Parameters
color: Color image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data as a vector of column vectors. Each column vector is 4-dimension and contains X,Y,Z,1 normalized coordinates of a point.

Definition at line 427 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud,
unsigned char *const  data_infrared,
unsigned char *const  data_infrared2 = NULL,
const rs::stream &  stream_color = rs::stream::color,
const rs::stream &  stream_depth = rs::stream::depth,
const rs::stream &  stream_infrared = rs::stream::infrared,
const rs::stream &  stream_infrared2 = rs::stream::infrared2 
)

Acquire data from RealSense device.

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.
data_infrared2: Infrared (for the second IR camera if available) image buffer or NULL if not wanted.
stream_color: Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth).
stream_depth: Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2).
stream_infrared: Type of infrared stream (only rs::stream::infrared should be possible).
stream_infrared2: Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera.

Definition at line 517 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< vpRGBa > &  color,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
color: Color image.
pointcloud: Point cloud data information.

Definition at line 687 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< vpRGBa > &  color,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
color: Color image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data information.

Definition at line 712 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( vpImage< vpRGBa > &  color,
vpImage< uint16_t > &  infrared,
vpImage< uint16_t > &  depth,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud 
)

Acquire data from RealSense device.

Parameters
color: Color image.
infrared: Infrared image.
depth: Depth image.
pointcloud: Point cloud data with texture information.

Definition at line 774 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud,
pcl::PointCloud< pcl::PointXYZ >::Ptr &  pointcloud,
unsigned char *const  data_infrared,
unsigned char *const  data_infrared2 = NULL,
const rs::stream &  stream_color = rs::stream::color,
const rs::stream &  stream_depth = rs::stream::depth,
const rs::stream &  stream_infrared = rs::stream::infrared,
const rs::stream &  stream_infrared2 = rs::stream::infrared2 
)

Acquire data from RealSense device.

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.
data_infrared2: Infrared (for the second IR camera if available) image buffer or NULL if not wanted.
stream_color: Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth).
stream_depth: Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2).
stream_infrared: Type of infrared stream (only rs::stream::infrared should be possible).
stream_infrared2: Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera.

Definition at line 842 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::acquire ( unsigned char *const  data_image,
unsigned char *const  data_depth,
std::vector< vpColVector > *const  data_pointCloud,
pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  pointcloud,
unsigned char *const  data_infrared,
unsigned char *const  data_infrared2 = NULL,
const rs::stream &  stream_color = rs::stream::color,
const rs::stream &  stream_depth = rs::stream::depth,
const rs::stream &  stream_infrared = rs::stream::infrared,
const rs::stream &  stream_infrared2 = rs::stream::infrared2 
)

Acquire data from RealSense device.

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.
data_infrared2: Infrared (for the second IR camera if available) image buffer or NULL if not wanted.
stream_color: Type of color stream (e.g. rs::stream::color, rs::stream::rectified_color, rs::stream::color_aligned_to_depth).
stream_depth: Type of depth stream (e.g. rs::stream::depth, rs::stream::depth_aligned_to_color, rs::stream::depth_aligned_to_rectified_color, rs::stream::depth_aligned_to_infrared2).
stream_infrared: Type of infrared stream (only rs::stream::infrared should be possible).
stream_infrared2: Type of infrared2 stream (e.g. rs::stream::infrared2, rs::stream::infrared2_aligned_to_depth) if supported by the camera.

Definition at line 894 of file vpRealSense.cpp.

References vpException::fatalError, m_device, m_intrinsics, m_invalidDepthValue, m_max_Z, and open().

void vpRealSense::close ( )

Stop device streaming.

Examples:
grabRealSense.cpp, and testRealSense.cpp.

Definition at line 217 of file vpRealSense.cpp.

References m_device.

Referenced by ~vpRealSense().

vpCameraParameters vpRealSense::getCameraParameters ( const rs::stream &  stream,
vpCameraParameters::vpCameraParametersProjType  type = vpCameraParameters::perspectiveProjWithDistortion 
) const

Return camera parameters corresponding to a specific stream. This function has to be called after open().

Parameters
stream: color, depth, infrared or infrared2 stream for which camera intrinsic parameters are returned.
type: Indicate if the model should include distorsion paramater or not.
See Also
getIntrinsics()
Examples:
grabRealSense.cpp.

Definition at line 259 of file vpRealSense.cpp.

References getIntrinsics(), vpCameraParameters::initPersProjWithDistortion(), vpCameraParameters::initPersProjWithoutDistortion(), and vpCameraParameters::perspectiveProjWithDistortion.

rs::extrinsics vpRealSense::getExtrinsics ( const rs::stream &  from,
const rs::stream &  to 
) const

Get extrinsic transformation from one stream to an other. This function has to be called after open().

Parameters
from,to: color, depth, infrared or infrared2 stream between which camera extrinsic parameters are returned.
See Also
getTransformation()

Definition at line 306 of file vpRealSense.cpp.

References vpException::fatalError, and m_device.

Referenced by getTransformation().

rs::device* vpRealSense::getHandler ( ) const
inline

Get access to device handler.

Examples:
testRealSense.cpp.

Definition at line 355 of file vpRealSense.h.

rs::intrinsics vpRealSense::getIntrinsics ( const rs::stream &  stream) const

Get intrinsic parameters corresponding to the stream. This function has to be called after open().

Parameters
stream: color, depth, infrared or infrared2 stream for which camera intrinsic parameters are returned.
See Also
getCameraParameters()
Examples:
grabRealSense.cpp, and testRealSense.cpp.

Definition at line 283 of file vpRealSense.cpp.

References vpException::fatalError, m_device, and m_intrinsics.

Referenced by getCameraParameters().

float vpRealSense::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 364 of file vpRealSense.h.

int vpRealSense::getNumDevices ( ) const
inline

Get number of devices that are detected.

Definition at line 369 of file vpRealSense.h.

std::string vpRealSense::getSerialNumber ( ) const
inline

Get device serial number.

See Also
setDeviceBySerialNumber()

Definition at line 374 of file vpRealSense.h.

vpHomogeneousMatrix vpRealSense::getTransformation ( const rs::stream &  from,
const rs::stream &  to 
) const

Get extrinsic transformation from one stream to an other. This function has to be called after open().

Parameters
from,to: color, depth, infrared or infrared2 stream between which camera extrinsic parameters are returned.
See Also
getExtrinsics()
Examples:
grabRealSense.cpp.

Definition at line 326 of file vpRealSense.cpp.

References getExtrinsics().

void vpRealSense::initStream ( )
protected

Definition at line 67 of file vpRealSense.cpp.

References m_enableStreams, m_streamParams, m_streamPresets, and m_useStreamPresets.

Referenced by vpRealSense().

void vpRealSense::open ( )

Open access to the RealSense device and start the streaming.

Examples:
grabRealSense.cpp, and testRealSense.cpp.

Definition at line 99 of file vpRealSense.cpp.

References vpException::fatalError, m_context, m_device, m_enableStreams, m_intrinsics, m_num_devices, m_serial_no, m_streamParams, m_streamPresets, and m_useStreamPresets.

Referenced by acquire().

void vpRealSense::setDeviceBySerialNumber ( const std::string &  serial_no)

Set active RealSence device using its serial number.

Parameters
serial_no: Device serial number.
#include <visp3/sensor/vpRealSense.h>
int main()
{
rs.setDeviceBySerialNumber("541142003219");
rs.open();
}

Definition at line 242 of file vpRealSense.cpp.

References vpException::fatalError, m_num_devices, and m_serial_no.

void vpRealSense::setEnableStream ( const rs::stream &  stream,
const bool  status 
)

Enable or disable a stream.

Parameters
stream: Stream type (color / depth / infrared).
status: Stream status.
#include <visp3/sensor/vpRealSense.h>
int main()
{
rs.setEnableStream(rs::stream::color, true);
rs.setEnableStream(rs::stream::depth, false);
rs.setEnableStream(rs::stream::infrared, false);
rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30));
rs.open();
//[...]
}
Examples:
testRealSense.cpp.

Definition at line 615 of file vpRealSense.cpp.

References m_enableStreams.

void vpRealSense::setInvalidDepthValue ( const 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 404 of file vpRealSense.h.

void vpRealSense::setStreamSettings ( const rs::stream &  stream,
const rs::preset &  preset 
)

Set stream settings.

Parameters
stream: Stream type (color / depth / infrared).
preset: Preset to use.
Examples:
testRealSense.cpp.

Definition at line 556 of file vpRealSense.cpp.

References m_streamPresets, and m_useStreamPresets.

void vpRealSense::setStreamSettings ( const rs::stream &  stream,
const vpRsStreamParams params 
)

Set stream settings.

Parameters
stream: Stream type (color / depth / infrared).
params: Stream parameters to use.
Note
You can find the stream settings of the different Intel RealSense cameras at this url.
#include <visp3/sensor/vpRealSense.h>
int main()
{
rs.setEnableStream(rs::stream::color, true);
rs.setEnableStream(rs::stream::depth, false);
rs.setEnableStream(rs::stream::infrared, false);
rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30));
rs.open();
//[...]
}

Definition at line 587 of file vpRealSense.cpp.

References m_streamParams, and m_useStreamPresets.

Friends And Related Function Documentation

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

Return information from sensor.

Parameters
os: Input stream.
rs: RealSense interface.

The following example shows how to use this method.

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

Definition at line 953 of file vpRealSense.cpp.

Member Data Documentation

rs::context vpRealSense::m_context
protected

Definition at line 412 of file vpRealSense.h.

Referenced by open().

rs::device* vpRealSense::m_device
protected

Definition at line 413 of file vpRealSense.h.

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

std::map<rs::stream, bool> vpRealSense::m_enableStreams
protected

Definition at line 418 of file vpRealSense.h.

Referenced by initStream(), open(), and setEnableStream().

std::map<rs::stream, rs::intrinsics> vpRealSense::m_intrinsics
protected

Definition at line 416 of file vpRealSense.h.

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

float vpRealSense::m_invalidDepthValue
protected

Definition at line 422 of file vpRealSense.h.

Referenced by acquire().

float vpRealSense::m_max_Z
protected

Maximal Z depth in meter.

Definition at line 417 of file vpRealSense.h.

Referenced by acquire().

int vpRealSense::m_num_devices
protected

Definition at line 414 of file vpRealSense.h.

Referenced by open(), and setDeviceBySerialNumber().

std::string vpRealSense::m_serial_no
protected

Definition at line 415 of file vpRealSense.h.

Referenced by open(), and setDeviceBySerialNumber().

std::map<rs::stream, vpRsStreamParams> vpRealSense::m_streamParams
protected

Definition at line 421 of file vpRealSense.h.

Referenced by initStream(), open(), and setStreamSettings().

std::map<rs::stream, rs::preset> vpRealSense::m_streamPresets
protected

Definition at line 420 of file vpRealSense.h.

Referenced by initStream(), open(), and setStreamSettings().

std::map<rs::stream, bool> vpRealSense::m_useStreamPresets
protected

Definition at line 419 of file vpRealSense.h.

Referenced by initStream(), open(), and setStreamSettings().