Visual Servoing Platform  version 3.1.0
testRealSense2_SR300.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Test Intel RealSense acquisition with librealsense2.
33  *
34  *****************************************************************************/
35 
41 #include <iostream>
42 
43 #include <visp3/core/vpConfig.h>
44 
45 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
46  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
47 
48 #include <visp3/core/vpImage.h>
49 #include <visp3/core/vpImageConvert.h>
50 #include <visp3/gui/vpDisplayGDI.h>
51 #include <visp3/gui/vpDisplayX.h>
52 #include <visp3/sensor/vpRealSense2.h>
53 
54 #ifdef VISP_HAVE_PCL
55 #include <pcl/visualization/cloud_viewer.h>
56 #include <pcl/visualization/pcl_visualizer.h>
57 #include <thread>
58 #endif
59 
60 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
61 #include <opencv2/core.hpp>
62 #include <opencv2/highgui.hpp>
63 #endif
64 
65 namespace
66 {
67 #ifdef VISP_HAVE_PCL
68 // Global variables
69 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
70 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
71 bool cancelled = false, update_pointcloud = false;
72 
73 class ViewerWorker
74 {
75 public:
76  explicit ViewerWorker(const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
77 
78  void run()
79  {
80  std::string date = vpTime::getDateTime();
81  pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
82  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
83  pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
84  pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
85 
86  viewer->setBackgroundColor(0, 0, 0);
87  viewer->initCameraParameters();
88  viewer->setPosition(640 + 80, 480 + 80);
89  viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
90  viewer->setSize(640, 480);
91 
92  bool init = true;
93  bool local_update = false, local_cancelled = false;
94  while (!local_cancelled) {
95  {
96  std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
97 
98  if (lock.owns_lock()) {
99  local_update = update_pointcloud;
100  update_pointcloud = false;
101  local_cancelled = cancelled;
102 
103  if (local_update) {
104  if (m_colorMode) {
105  local_pointcloud_color = pointcloud_color->makeShared();
106  } else {
107  local_pointcloud = pointcloud->makeShared();
108  }
109  }
110  }
111  }
112 
113  if (local_update && !local_cancelled) {
114  local_update = false;
115 
116  if (init) {
117  if (m_colorMode) {
118  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
119  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
120  "RGB sample cloud");
121  } else {
122  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
123  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
124  }
125  init = false;
126  } else {
127  if (m_colorMode) {
128  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
129  } else {
130  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
131  }
132  }
133  }
134 
135  viewer->spinOnce(5);
136  }
137 
138  std::cout << "End of point cloud display thread" << std::endl;
139  }
140 
141 private:
142  bool m_colorMode;
143  std::mutex &m_mutex;
144 };
145 
146 void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud)
147 {
148  auto vf = depth_frame.as<rs2::video_frame>();
149  const int width = vf.get_width();
150  const int height = vf.get_height();
151  pointcloud.resize((size_t)(width * height));
152 
153  rs2::pointcloud pc;
154  rs2::points points = pc.calculate(depth_frame);
155  auto vertices = points.get_vertices();
156  vpColVector v(4);
157  for (size_t i = 0; i < points.size(); i++) {
158  if (vertices[i].z) {
159  v[0] = vertices[i].x;
160  v[1] = vertices[i].y;
161  v[2] = vertices[i].z;
162  v[3] = 1.0;
163  } else {
164  v[0] = 0.0;
165  v[1] = 0.0;
166  v[2] = 0.0;
167  v[3] = 1.0;
168  }
169 
170  pointcloud[i] = v;
171  }
172 }
173 #endif
174 
175 void getNativeFrame(const rs2::frame &frame, unsigned char *const data)
176 {
177  auto vf = frame.as<rs2::video_frame>();
178  int size = vf.get_width() * vf.get_height();
179 
180  switch (frame.get_profile().format()) {
181  case RS2_FORMAT_RGB8:
182  case RS2_FORMAT_BGR8:
183  memcpy(data, (void *)frame.get_data(), size * 3);
184  break;
185 
186  case RS2_FORMAT_RGBA8:
187  case RS2_FORMAT_BGRA8:
188  memcpy(data, (void *)frame.get_data(), size * 4);
189  break;
190 
191  case RS2_FORMAT_Y16:
192  case RS2_FORMAT_Z16:
193  memcpy(data, (unsigned char *)frame.get_data(), size * 2);
194  break;
195 
196  case RS2_FORMAT_Y8:
197  memcpy(data, (unsigned char *)frame.get_data(), size);
198  break;
199 
200  default:
201  break;
202  }
203 }
204 
205 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
206 void frame_to_mat(const rs2::frame &f, cv::Mat &img)
207 {
208  auto vf = f.as<rs2::video_frame>();
209  const int w = vf.get_width();
210  const int h = vf.get_height();
211  const int size = w * h;
212 
213  if (f.get_profile().format() == RS2_FORMAT_BGR8) {
214  memcpy(img.ptr<cv::Vec3b>(), f.get_data(), size * 3);
215  } else if (f.get_profile().format() == RS2_FORMAT_RGB8) {
216  cv::Mat tmp(h, w, CV_8UC3, (void *)f.get_data(), cv::Mat::AUTO_STEP);
217  cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR);
218  } else if (f.get_profile().format() == RS2_FORMAT_Y8) {
219  memcpy(img.ptr<uchar>(), f.get_data(), size);
220  }
221 }
222 #endif
223 }
224 
225 int main(int argc, char *argv[])
226 {
227  bool pcl_color = false;
228  bool show_info = false;
229 
230  for (int i = 1; i < argc; i++) {
231  if (std::string(argv[i]) == "--pcl_color") {
232  pcl_color = true;
233  } else if (std::string(argv[i]) == "--show_info") {
234  show_info = true;
235  }
236  }
237 
238  if (show_info) {
239  vpRealSense2 rs;
240  rs.open();
241  std::cout << "RealSense:\n" << rs << std::endl;
242  return EXIT_SUCCESS;
243  }
244 
245  vpRealSense2 rs;
246  rs2::config config;
247  config.enable_stream(RS2_STREAM_COLOR, 1920, 1080, RS2_FORMAT_RGBA8, 30);
248  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
249  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y16, 30);
250  rs.open(config);
251 
252  rs2::pipeline_profile &profile = rs.getPipelineProfile();
253  auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
254  vpImage<vpRGBa> color((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
255 
256  auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
257  vpImage<vpRGBa> depth_color((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
258  vpImage<uint16_t> depth_raw((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
259 
260  auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
261  vpImage<unsigned char> infrared((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
262  vpImage<uint16_t> infrared_raw((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
263 
264 #ifdef VISP_HAVE_X11
265  vpDisplayX d1, d2, d3;
266 #else
267  vpDisplayGDI d1, d2, d3;
268 #endif
269  d1.init(color, 0, 0, "Color");
270  d2.init(depth_color, color.getWidth(), 0, "Depth");
271  d3.init(infrared, 0, color.getHeight() + 100, "Infrared");
272 
273  std::vector<vpColVector> pointcloud_colvector;
274 #ifdef VISP_HAVE_PCL
275  std::mutex mutex;
276  ViewerWorker viewer_colvector(false, mutex);
277  std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
278 #endif
279 
280  rs2::pipeline &pipe = rs.getPipeline();
281 
282  std::cout << "Color intrinsics:\n"
284  << std::endl;
285  std::cout << "Color intrinsics:\n"
286  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
287 
288  std::cout << "Depth intrinsics:\n"
290  << std::endl;
291  std::cout << "Depth intrinsics:\n"
292  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
293 
294  std::cout << "Infrared intrinsics:\n"
296  << std::endl;
297  std::cout << "Infrared intrinsics:\n"
299  << std::endl;
300 
301  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
302  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
303 
304  std::vector<double> time_vector;
305  double t_begin = vpTime::measureTimeMs();
306  while (vpTime::measureTimeMs() - t_begin < 10000) {
307  double t = vpTime::measureTimeMs();
308 
309  auto data = pipe.wait_for_frames();
310  auto color_frame = data.get_color_frame();
311  getNativeFrame(color_frame, (unsigned char *)color.bitmap);
312 
313  auto depth_frame = data.get_depth_frame();
314  getNativeFrame(depth_frame, (unsigned char *)depth_raw.bitmap);
315 
316  auto infrared_frame = data.first(RS2_STREAM_INFRARED);
317  getNativeFrame(infrared_frame, (unsigned char *)infrared_raw.bitmap);
318 
319 #ifdef VISP_HAVE_PCL
320  getPointcloud(depth_frame, pointcloud_colvector);
321 
322  {
323  std::lock_guard<std::mutex> lock(mutex);
324 
325  pointcloud->width = depth_profile.width();
326  pointcloud->height = depth_profile.height();
327  pointcloud->points.resize(pointcloud_colvector.size());
328  for (size_t i = 0; i < pointcloud_colvector.size(); i++) {
329  pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
330  pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
331  pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
332  }
333 
334  update_pointcloud = true;
335  }
336 #endif
337 
338  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
339  vpImageConvert::convert(infrared_raw, infrared);
340 
341  vpDisplay::display(color);
342  vpDisplay::display(depth_color);
343  vpDisplay::display(infrared);
344 
345  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
346 
347  vpDisplay::flush(color);
348  vpDisplay::flush(depth_color);
349  vpDisplay::flush(infrared);
350 
351  time_vector.push_back(vpTime::measureTimeMs() - t);
352  if (vpDisplay::getClick(color, false))
353  break;
354  }
355 
356  rs.close();
357  d1.close(color);
358  d2.close(depth_color);
359  d3.close(infrared);
360 
361 #ifdef VISP_HAVE_PCL
362  {
363  std::lock_guard<std::mutex> lock(mutex);
364  cancelled = true;
365  }
366 
367  viewer_colvector_thread.join();
368 #endif
369  std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector)
370  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
371 
372  config.disable_all_streams();
373  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
374  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
375  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
376  rs.open(config);
377 
378  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
379  color.init((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
380 
381  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
382  depth_color.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
383  depth_raw.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
384 
385  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
386  infrared.init((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
387 
388  d1.init(color, 0, 0, "Color");
389  d2.init(depth_color, color.getWidth(), 0, "Depth");
390  d3.init(infrared, 0, color.getHeight() + 100, "Infrared");
391 
392 #ifdef VISP_HAVE_PCL
393  cancelled = false;
394  ViewerWorker viewer(pcl_color, mutex);
395  std::thread viewer_thread(&ViewerWorker::run, &viewer);
396 #endif
397 
398  std::cout << "\n" << std::endl;
399  std::cout << "Color intrinsics:\n"
401  << std::endl;
402  std::cout << "Color intrinsics:\n"
403  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
404 
405  std::cout << "Depth intrinsics:\n"
407  << std::endl;
408  std::cout << "Depth intrinsics:\n"
409  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
410 
411  std::cout << "Infrared intrinsics:\n"
413  << std::endl;
414  std::cout << "Infrared intrinsics:\n"
416  << std::endl;
417 
418  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
419  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
420 
421  time_vector.clear();
422  t_begin = vpTime::measureTimeMs();
423  while (vpTime::measureTimeMs() - t_begin < 10000) {
424  double t = vpTime::measureTimeMs();
425 
426 #ifdef VISP_HAVE_PCL
427  {
428  std::lock_guard<std::mutex> lock(mutex);
429 
430  if (pcl_color) {
431  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud_color,
432  (unsigned char *)infrared.bitmap);
433  } else {
434  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud,
435  (unsigned char *)infrared.bitmap);
436  }
437 
438  update_pointcloud = true;
439  }
440 #else
441  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL,
442  (unsigned char *)infrared.bitmap);
443 #endif
444 
445  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
446 
447  vpDisplay::display(color);
448  vpDisplay::display(depth_color);
449  vpDisplay::display(infrared);
450 
451  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
452 
453  vpDisplay::flush(color);
454  vpDisplay::flush(depth_color);
455  vpDisplay::flush(infrared);
456 
457  time_vector.push_back(vpTime::measureTimeMs() - t);
458  if (vpDisplay::getClick(color, false))
459  break;
460  }
461 
462 #ifdef VISP_HAVE_PCL
463  {
464  std::lock_guard<std::mutex> lock(mutex);
465  cancelled = true;
466  }
467 
468  viewer_thread.join();
469 #endif
470 
471  d1.close(color);
472  d2.close(depth_color);
473  d3.close(infrared);
474  std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector)
475  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
476 
477 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
478  rs.close();
479  config.disable_all_streams();
480  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
481  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
482  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
483  rs.open(config);
484 
485  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
486  cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
487 
488  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
489  cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
490  rs2::colorizer color_map;
491 
492  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
493  cv::Mat mat_infrared(infrared_profile.height(), infrared_profile.width(), CV_8U);
494 
495  time_vector.clear();
496  t_begin = vpTime::measureTimeMs();
497  while (vpTime::measureTimeMs() - t_begin < 10000) {
498  double t = vpTime::measureTimeMs();
499 
500  auto data = pipe.wait_for_frames();
501  frame_to_mat(data.get_color_frame(), mat_color);
502  frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
503  frame_to_mat(data.first(RS2_STREAM_INFRARED), mat_infrared);
504 
505  cv::imshow("OpenCV color", mat_color);
506  cv::imshow("OpenCV depth", mat_depth);
507  cv::imshow("OpenCV infrared", mat_infrared);
508 
509  time_vector.push_back(vpTime::measureTimeMs() - t);
510  if (cv::waitKey(10) == 27)
511  break;
512  }
513 
514  std::cout << "Acquisition3 - Mean time: " << vpMath::getMean(time_vector)
515  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
516 #endif
517 
518  return EXIT_SUCCESS;
519 }
520 
521 #else
522 int main()
523 {
524 #if !defined(VISP_HAVE_REALSENSE2)
525  std::cout << "Install librealsense2 to make this test work." << std::endl;
526 #endif
527 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
528  std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) "
529  "to make this test work"
530  << std::endl;
531 #endif
532 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
533  std::cout << "X11 or GDI are needed." << std::endl;
534 #endif
535  return 0;
536 }
537 #endif
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:320
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void close(vpImage< unsigned char > &I)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:222
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:129
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
void open(const rs2::config &cfg=rs2::config())
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:88
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
Definition: vpTime.cpp:345
static const vpColor red
Definition: vpColor.h:180
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:202
static void display(const vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &grey)
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:317
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)