42#include <visp3/core/vpConfig.h>
44#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY)
46#include <visp3/core/vpTime.h>
47#include <visp3/core/vpImageConvert.h>
48#include <visp3/gui/vpDisplayFactory.h>
49#include <visp3/gui/vpDisplayPCL.h>
50#include <visp3/sensor/vpRealSense2.h>
54#ifdef ENABLE_VISP_NAMESPACE
58#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
68 std::cout <<
"Product line: " << product_line << std::endl;
70 if (product_line ==
"T200") {
71 std::cout <<
"This example doesn't support T200 product line family !" << std::endl;
75 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
76 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
77 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
84 std::cout <<
"Extrinsics cMd: \n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
85 std::cout <<
"Extrinsics dMc: \n" << rs.
getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_COLOR) << std::endl;
86 std::cout <<
"Extrinsics cMi: \n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_INFRARED) << std::endl;
87 std::cout <<
"Extrinsics dMi: \n" << rs.
getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_INFRARED) << std::endl;
90 static_cast<unsigned int>(rs.
getIntrinsics(RS2_STREAM_COLOR).width));
92 static_cast<unsigned int>(rs.
getIntrinsics(RS2_STREAM_INFRARED).width));
94 static_cast<unsigned int>(rs.
getIntrinsics(RS2_STREAM_DEPTH).width));
97#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
99 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
100#if defined(VISP_HAVE_PCL_VISUALIZATION)
102 pcl_viewer.startThread(std::ref(mutex), pointcloud_color);
106#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
119#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
121 std::lock_guard<std::mutex> lock(mutex);
122 rs.
acquire(
reinterpret_cast<unsigned char *
>(
color.bitmap),
reinterpret_cast<unsigned char *
>(
depth.bitmap),
nullptr, pointcloud_color,
123 reinterpret_cast<unsigned char *
>(infrared.bitmap));
126 rs.
acquire(
reinterpret_cast<unsigned char *
>(
color.bitmap),
reinterpret_cast<unsigned char *
>(
depth.bitmap),
nullptr,
reinterpret_cast<unsigned char *
>(infrared.bitmap));
147 std::cout <<
"RealSense sensor characteristics: \n" << rs << std::endl;
150 std::cerr <<
"RealSense error " <<
e.what() << std::endl;
152 catch (
const std::exception &e) {
153 std::cerr <<
e.what() << std::endl;
156#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
167#if !defined(VISP_HAVE_REALSENSE2)
168 std::cout <<
"You do not have realsense2 SDK functionality enabled..." << std::endl;
169 std::cout <<
"Tip:" << std::endl;
170 std::cout <<
"- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl;
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Class that defines generic functionalities for display.
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)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
Definition of the vpImage class member functions.
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
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
std::string getProductLine()
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")