41 #include <visp3/core/vpConfig.h>
43 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
45 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
47 #include <pcl/visualization/cloud_viewer.h>
48 #include <pcl/visualization/pcl_visualizer.h>
52 #include <visp3/core/vpImage.h>
53 #include <visp3/core/vpImageConvert.h>
54 #include <visp3/gui/vpDisplayGDI.h>
55 #include <visp3/gui/vpDisplayX.h>
56 #include <visp3/sensor/vpRealSense2.h>
58 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
59 #include <opencv2/core.hpp>
60 #include <opencv2/highgui.hpp>
63 #ifdef ENABLE_VISP_NAMESPACE
69 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
71 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
72 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
73 bool cancelled =
false, update_pointcloud =
false;
78 explicit ViewerWorker(
bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) { }
83 pcl::visualization::PCLVisualizer::Ptr viewer(
new pcl::visualization::PCLVisualizer(
"3D Viewer " + date));
84 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
85 pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
86 pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(
new pcl::PointCloud<pcl::PointXYZRGB>());
88 viewer->setBackgroundColor(0, 0, 0);
89 viewer->initCameraParameters();
90 viewer->setPosition(640 + 80, 480 + 80);
91 viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
92 viewer->setSize(640, 480);
95 bool local_update =
false, local_cancelled =
false;
96 while (!local_cancelled) {
98 std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
100 if (lock.owns_lock()) {
101 local_update = update_pointcloud;
102 update_pointcloud =
false;
103 local_cancelled = cancelled;
107 local_pointcloud_color = pointcloud_color->makeShared();
110 local_pointcloud = pointcloud->makeShared();
116 if (local_update && !local_cancelled) {
117 local_update =
false;
121 viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
122 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
126 viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
127 viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
"sample cloud");
133 viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb,
"RGB sample cloud");
136 viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud,
"sample cloud");
144 std::cout <<
"End of point cloud display thread" << std::endl;
152 void getPointcloud(
const rs2::depth_frame &depth_frame, std::vector<vpColVector> &point_cloud)
154 auto vf = depth_frame.as<rs2::video_frame>();
155 const int width = vf.get_width();
156 const int height = vf.get_height();
157 point_cloud.resize((
size_t)(width * height));
160 rs2::points points = pc.calculate(depth_frame);
161 auto vertices = points.get_vertices();
163 for (
size_t i = 0; i < points.size(); i++) {
165 v[0] = vertices[i].x;
166 v[1] = vertices[i].y;
167 v[2] = vertices[i].z;
182 void getNativeFrame(
const rs2::frame &frame,
unsigned char *
const data)
184 auto vf = frame.as<rs2::video_frame>();
185 int size = vf.get_width() * vf.get_height();
187 switch (frame.get_profile().format()) {
188 case RS2_FORMAT_RGB8:
189 case RS2_FORMAT_BGR8:
190 memcpy(data, (
void *)frame.get_data(), size * 3);
193 case RS2_FORMAT_RGBA8:
194 case RS2_FORMAT_BGRA8:
195 memcpy(data, (
void *)frame.get_data(), size * 4);
200 memcpy(data, (
unsigned char *)frame.get_data(), size * 2);
204 memcpy(data, (
unsigned char *)frame.get_data(), size);
212 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
213 void frame_to_mat(
const rs2::frame &f, cv::Mat &img)
215 auto vf = f.as<rs2::video_frame>();
216 const int w = vf.get_width();
217 const int h = vf.get_height();
218 const int size = w * h;
220 if (f.get_profile().format() == RS2_FORMAT_BGR8) {
221 memcpy(
static_cast<void *
>(img.ptr<cv::Vec3b>()), f.get_data(), size * 3);
223 else if (f.get_profile().format() == RS2_FORMAT_RGB8) {
224 cv::Mat tmp(h, w, CV_8UC3, (
void *)f.get_data(), cv::Mat::AUTO_STEP);
225 cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR);
227 else if (f.get_profile().format() == RS2_FORMAT_Y8) {
228 memcpy(img.ptr<uchar>(), f.get_data(), size);
234 int main(
int argc,
char *argv[])
236 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
237 bool pcl_color =
false;
239 bool show_info =
false;
241 for (
int i = 1; i < argc; i++) {
242 if (std::string(argv[i]) ==
"--show_info") {
245 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
246 else if (std::string(argv[i]) ==
"--pcl_color") {
250 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
251 std::cout << argv[0] <<
" [--show_info]"
252 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
264 std::cout <<
"RealSense:\n" << rs << std::endl;
270 config.enable_stream(RS2_STREAM_COLOR, 1920, 1080, RS2_FORMAT_RGBA8, 30);
271 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
272 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y16, 30);
276 auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
277 vpImage<vpRGBa> color((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
279 auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
280 vpImage<vpRGBa> depth_color((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
281 vpImage<uint16_t> depth_raw((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
283 auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
284 vpImage<unsigned char> infrared((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
285 vpImage<uint16_t> infrared_raw((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
288 vpDisplayX d1, d2, d3;
292 d1.
init(color, 0, 0,
"Color");
293 d2.init(depth_color, color.getWidth(), 0,
"Depth");
294 d3.init(infrared, 0, color.getHeight() + 100,
"Infrared");
296 std::vector<vpColVector> pointcloud_colvector;
297 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
299 ViewerWorker viewer_colvector(
false, mutex);
300 std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
305 std::cout <<
"Color intrinsics:\n"
308 std::cout <<
"Color intrinsics:\n"
311 std::cout <<
"Depth intrinsics:\n"
314 std::cout <<
"Depth intrinsics:\n"
317 std::cout <<
"Infrared intrinsics:\n"
320 std::cout <<
"Infrared intrinsics:\n"
324 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
325 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
327 std::vector<double> time_vector;
332 auto data = pipe.wait_for_frames();
333 auto color_frame = data.get_color_frame();
334 getNativeFrame(color_frame, (
unsigned char *)color.bitmap);
336 auto depth_frame = data.get_depth_frame();
337 getNativeFrame(depth_frame, (
unsigned char *)depth_raw.bitmap);
339 auto infrared_frame = data.first(RS2_STREAM_INFRARED);
340 getNativeFrame(infrared_frame, (
unsigned char *)infrared_raw.bitmap);
342 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
343 getPointcloud(depth_frame, pointcloud_colvector);
346 std::lock_guard<std::mutex> lock(mutex);
348 pointcloud->width = depth_profile.width();
349 pointcloud->height = depth_profile.height();
350 pointcloud->points.resize(pointcloud_colvector.size());
351 for (
size_t i = 0; i < pointcloud_colvector.size(); i++) {
352 pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
353 pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
354 pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
357 update_pointcloud =
true;
381 d2.close(depth_color);
384 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
386 std::lock_guard<std::mutex> lock(mutex);
390 viewer_colvector_thread.join();
392 std::cout <<
"Acquisition1 - Mean time: " <<
vpMath::getMean(time_vector)
393 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
395 config.disable_all_streams();
396 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
397 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
398 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
401 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
402 color.init((
unsigned int)color_profile.height(), (
unsigned int)color_profile.width());
404 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
405 depth_color.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
406 depth_raw.init((
unsigned int)depth_profile.height(), (
unsigned int)depth_profile.width());
408 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
409 infrared.init((
unsigned int)infrared_profile.height(), (
unsigned int)infrared_profile.width());
411 d1.init(color, 0, 0,
"Color");
412 d2.init(depth_color, color.getWidth(), 0,
"Depth");
413 d3.init(infrared, 0, color.getHeight() + 100,
"Infrared");
415 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
417 ViewerWorker viewer(pcl_color, mutex);
418 std::thread viewer_thread(&ViewerWorker::run, &viewer);
421 std::cout <<
"\n" << std::endl;
422 std::cout <<
"Color intrinsics:\n"
425 std::cout <<
"Color intrinsics:\n"
428 std::cout <<
"Depth intrinsics:\n"
431 std::cout <<
"Depth intrinsics:\n"
434 std::cout <<
"Infrared intrinsics:\n"
437 std::cout <<
"Infrared intrinsics:\n"
441 std::cout <<
"depth_M_color:\n" << rs.
getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
442 std::cout <<
"color_M_infrared:\n" << rs.
getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
449 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
451 std::lock_guard<std::mutex> lock(mutex);
454 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap,
nullptr, pointcloud_color,
455 (
unsigned char *)infrared.bitmap);
458 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap,
nullptr, pointcloud,
459 (
unsigned char *)infrared.bitmap);
462 update_pointcloud =
true;
465 rs.
acquire((
unsigned char *)color.bitmap, (
unsigned char *)depth_raw.bitmap,
nullptr,
466 (
unsigned char *)infrared.bitmap);
486 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
488 std::lock_guard<std::mutex> lock(mutex);
492 viewer_thread.join();
496 d2.close(depth_color);
498 std::cout <<
"Acquisition2 - Mean time: " <<
vpMath::getMean(time_vector)
499 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
501 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
503 config.disable_all_streams();
504 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
505 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
506 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
509 color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
510 cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
512 depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
513 cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
514 rs2::colorizer color_map;
516 infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
517 cv::Mat mat_infrared(infrared_profile.height(), infrared_profile.width(), CV_8U);
524 auto data = pipe.wait_for_frames();
525 frame_to_mat(data.get_color_frame(), mat_color);
526 #if (RS2_API_VERSION >= ((2 * 10000) + (16 * 100) + 0))
527 frame_to_mat(data.get_depth_frame().apply_filter(color_map), mat_depth);
529 frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
531 frame_to_mat(data.first(RS2_STREAM_INFRARED), mat_infrared);
533 cv::imshow(
"OpenCV color", mat_color);
534 cv::imshow(
"OpenCV depth", mat_depth);
535 cv::imshow(
"OpenCV infrared", mat_infrared);
538 if (cv::waitKey(10) == 27)
542 std::cout <<
"Acquisition3 - Mean time: " <<
vpMath::getMean(time_vector)
543 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
546 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
549 ViewerWorker viewer_colvector2(
false, mutex);
550 std::thread viewer_colvector_thread2(&ViewerWorker::run, &viewer_colvector2);
554 config.disable_all_streams();
555 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
556 config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
557 config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
564 rs.
acquire(
nullptr,
nullptr, &pointcloud_colvector,
nullptr,
nullptr);
567 std::lock_guard<std::mutex> lock(mutex);
568 pointcloud->width = 640;
569 pointcloud->height = 480;
570 pointcloud->points.resize(pointcloud_colvector.size());
571 for (
size_t i = 0; i < pointcloud_colvector.size(); i++) {
572 pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
573 pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
574 pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
577 update_pointcloud =
true;
585 std::lock_guard<std::mutex> lock(mutex);
589 viewer_colvector_thread2.join();
591 std::cout <<
"Acquisition4 - Mean time: " <<
vpMath::getMean(time_vector)
592 <<
" ms ; Median time: " <<
vpMath::getMedian(time_vector) <<
" ms" << std::endl;
601 #if !defined(VISP_HAVE_REALSENSE2)
602 std::cout <<
"Install librealsense2 to make this test work." << std::endl;
604 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
605 std::cout <<
"X11 or GDI are needed." << std::endl;
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Display for windows using GDI (available on any windows 32 platform).
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="") VP_OVERRIDE
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)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static double getMedian(const std::vector< double > &v)
static double getMean(const std::vector< double > &v)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
bool open(const rs2::config &cfg=rs2::config())
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
VISP_EXPORT double measureTimeMs()