Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
testRealSense2_SR300.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 #include <mutex>
59 #endif
60 
61 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
62 #include <opencv2/core.hpp>
63 #include <opencv2/highgui.hpp>
64 #endif
65 
66 namespace
67 {
68 #ifdef VISP_HAVE_PCL
69 // Global variables
70 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
71 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
72 bool cancelled = false, update_pointcloud = false;
73 
74 class ViewerWorker
75 {
76 public:
77  explicit ViewerWorker(const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
78 
79  void run()
80  {
81  std::string date = vpTime::getDateTime();
82  pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
83  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
84  pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
85  pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
86 
87  viewer->setBackgroundColor(0, 0, 0);
88  viewer->initCameraParameters();
89  viewer->setPosition(640 + 80, 480 + 80);
90  viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
91  viewer->setSize(640, 480);
92 
93  bool init = true;
94  bool local_update = false, local_cancelled = false;
95  while (!local_cancelled) {
96  {
97  std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
98 
99  if (lock.owns_lock()) {
100  local_update = update_pointcloud;
101  update_pointcloud = false;
102  local_cancelled = cancelled;
103 
104  if (local_update) {
105  if (m_colorMode) {
106  local_pointcloud_color = pointcloud_color->makeShared();
107  } else {
108  local_pointcloud = pointcloud->makeShared();
109  }
110  }
111  }
112  }
113 
114  if (local_update && !local_cancelled) {
115  local_update = false;
116 
117  if (init) {
118  if (m_colorMode) {
119  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
120  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
121  "RGB sample cloud");
122  } else {
123  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
124  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
125  }
126  init = false;
127  } else {
128  if (m_colorMode) {
129  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
130  } else {
131  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
132  }
133  }
134  }
135 
136  viewer->spinOnce(5);
137  }
138 
139  std::cout << "End of point cloud display thread" << std::endl;
140  }
141 
142 private:
143  bool m_colorMode;
144  std::mutex &m_mutex;
145 };
146 
147 void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud)
148 {
149  auto vf = depth_frame.as<rs2::video_frame>();
150  const int width = vf.get_width();
151  const int height = vf.get_height();
152  pointcloud.resize((size_t)(width * height));
153 
154  rs2::pointcloud pc;
155  rs2::points points = pc.calculate(depth_frame);
156  auto vertices = points.get_vertices();
157  vpColVector v(4);
158  for (size_t i = 0; i < points.size(); i++) {
159  if (vertices[i].z) {
160  v[0] = vertices[i].x;
161  v[1] = vertices[i].y;
162  v[2] = vertices[i].z;
163  v[3] = 1.0;
164  } else {
165  v[0] = 0.0;
166  v[1] = 0.0;
167  v[2] = 0.0;
168  v[3] = 1.0;
169  }
170 
171  pointcloud[i] = v;
172  }
173 }
174 #endif
175 
176 void getNativeFrame(const rs2::frame &frame, unsigned char *const data)
177 {
178  auto vf = frame.as<rs2::video_frame>();
179  int size = vf.get_width() * vf.get_height();
180 
181  switch (frame.get_profile().format()) {
182  case RS2_FORMAT_RGB8:
183  case RS2_FORMAT_BGR8:
184  memcpy(data, (void *)frame.get_data(), size * 3);
185  break;
186 
187  case RS2_FORMAT_RGBA8:
188  case RS2_FORMAT_BGRA8:
189  memcpy(data, (void *)frame.get_data(), size * 4);
190  break;
191 
192  case RS2_FORMAT_Y16:
193  case RS2_FORMAT_Z16:
194  memcpy(data, (unsigned char *)frame.get_data(), size * 2);
195  break;
196 
197  case RS2_FORMAT_Y8:
198  memcpy(data, (unsigned char *)frame.get_data(), size);
199  break;
200 
201  default:
202  break;
203  }
204 }
205 
206 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
207 void frame_to_mat(const rs2::frame &f, cv::Mat &img)
208 {
209  auto vf = f.as<rs2::video_frame>();
210  const int w = vf.get_width();
211  const int h = vf.get_height();
212  const int size = w * h;
213 
214  if (f.get_profile().format() == RS2_FORMAT_BGR8) {
215  memcpy(static_cast<void*>(img.ptr<cv::Vec3b>()), f.get_data(), size * 3);
216  } else if (f.get_profile().format() == RS2_FORMAT_RGB8) {
217  cv::Mat tmp(h, w, CV_8UC3, (void *)f.get_data(), cv::Mat::AUTO_STEP);
218  cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR);
219  } else if (f.get_profile().format() == RS2_FORMAT_Y8) {
220  memcpy(img.ptr<uchar>(), f.get_data(), size);
221  }
222 }
223 #endif
224 }
225 
226 int main(int argc, char *argv[])
227 {
228 #ifdef VISP_HAVE_PCL
229  bool pcl_color = false;
230 #endif
231  bool show_info = false;
232 
233  for (int i = 1; i < argc; i++) {
234  if (std::string(argv[i]) == "--show_info") {
235  show_info = true;
236  }
237 #ifdef VISP_HAVE_PCL
238  else if (std::string(argv[i]) == "--pcl_color") {
239  pcl_color = true;
240  }
241 #endif
242  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
243  std::cout << argv[0] << " [--show_info]"
244 #ifdef VISP_HAVE_PCL
245  << " [--pcl_color]"
246 #endif
247  << " [--help] [-h]"
248  << "\n";
249  return EXIT_SUCCESS;
250  }
251  }
252 
253  if (show_info) {
254  vpRealSense2 rs;
255  rs.open();
256  std::cout << "RealSense:\n" << rs << std::endl;
257  return EXIT_SUCCESS;
258  }
259 
260  vpRealSense2 rs;
261  rs2::config config;
262  config.enable_stream(RS2_STREAM_COLOR, 1920, 1080, RS2_FORMAT_RGBA8, 30);
263  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
264  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y16, 30);
265  rs.open(config);
266 
267  rs2::pipeline_profile &profile = rs.getPipelineProfile();
268  auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
269  vpImage<vpRGBa> color((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
270 
271  auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
272  vpImage<vpRGBa> depth_color((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
273  vpImage<uint16_t> depth_raw((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
274 
275  auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
276  vpImage<unsigned char> infrared((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
277  vpImage<uint16_t> infrared_raw((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
278 
279 #ifdef VISP_HAVE_X11
280  vpDisplayX d1, d2, d3;
281 #else
282  vpDisplayGDI d1, d2, d3;
283 #endif
284  d1.init(color, 0, 0, "Color");
285  d2.init(depth_color, color.getWidth(), 0, "Depth");
286  d3.init(infrared, 0, color.getHeight() + 100, "Infrared");
287 
288  std::vector<vpColVector> pointcloud_colvector;
289 #ifdef VISP_HAVE_PCL
290  std::mutex mutex;
291  ViewerWorker viewer_colvector(false, mutex);
292  std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
293 #endif
294 
295  rs2::pipeline &pipe = rs.getPipeline();
296 
297  std::cout << "Color intrinsics:\n"
299  << std::endl;
300  std::cout << "Color intrinsics:\n"
301  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
302 
303  std::cout << "Depth intrinsics:\n"
305  << std::endl;
306  std::cout << "Depth intrinsics:\n"
307  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
308 
309  std::cout << "Infrared intrinsics:\n"
311  << std::endl;
312  std::cout << "Infrared intrinsics:\n"
314  << std::endl;
315 
316  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
317  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
318 
319  std::vector<double> time_vector;
320  double t_begin = vpTime::measureTimeMs();
321  while (vpTime::measureTimeMs() - t_begin < 10000) {
322  double t = vpTime::measureTimeMs();
323 
324  auto data = pipe.wait_for_frames();
325  auto color_frame = data.get_color_frame();
326  getNativeFrame(color_frame, (unsigned char *)color.bitmap);
327 
328  auto depth_frame = data.get_depth_frame();
329  getNativeFrame(depth_frame, (unsigned char *)depth_raw.bitmap);
330 
331  auto infrared_frame = data.first(RS2_STREAM_INFRARED);
332  getNativeFrame(infrared_frame, (unsigned char *)infrared_raw.bitmap);
333 
334 #ifdef VISP_HAVE_PCL
335  getPointcloud(depth_frame, pointcloud_colvector);
336 
337  {
338  std::lock_guard<std::mutex> lock(mutex);
339 
340  pointcloud->width = depth_profile.width();
341  pointcloud->height = depth_profile.height();
342  pointcloud->points.resize(pointcloud_colvector.size());
343  for (size_t i = 0; i < pointcloud_colvector.size(); i++) {
344  pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
345  pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
346  pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
347  }
348 
349  update_pointcloud = true;
350  }
351 #endif
352 
353  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
354  vpImageConvert::convert(infrared_raw, infrared);
355 
356  vpDisplay::display(color);
357  vpDisplay::display(depth_color);
358  vpDisplay::display(infrared);
359 
360  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
361 
362  vpDisplay::flush(color);
363  vpDisplay::flush(depth_color);
364  vpDisplay::flush(infrared);
365 
366  time_vector.push_back(vpTime::measureTimeMs() - t);
367  if (vpDisplay::getClick(color, false))
368  break;
369  }
370 
371  rs.close();
372  d1.close(color);
373  d2.close(depth_color);
374  d3.close(infrared);
375 
376 #ifdef VISP_HAVE_PCL
377  {
378  std::lock_guard<std::mutex> lock(mutex);
379  cancelled = true;
380  }
381 
382  viewer_colvector_thread.join();
383 #endif
384  std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector)
385  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
386 
387  config.disable_all_streams();
388  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
389  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
390  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
391  rs.open(config);
392 
393  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
394  color.init((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
395 
396  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
397  depth_color.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
398  depth_raw.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
399 
400  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
401  infrared.init((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
402 
403  d1.init(color, 0, 0, "Color");
404  d2.init(depth_color, color.getWidth(), 0, "Depth");
405  d3.init(infrared, 0, color.getHeight() + 100, "Infrared");
406 
407 #ifdef VISP_HAVE_PCL
408  cancelled = false;
409  ViewerWorker viewer(pcl_color, mutex);
410  std::thread viewer_thread(&ViewerWorker::run, &viewer);
411 #endif
412 
413  std::cout << "\n" << std::endl;
414  std::cout << "Color intrinsics:\n"
416  << std::endl;
417  std::cout << "Color intrinsics:\n"
418  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
419 
420  std::cout << "Depth intrinsics:\n"
422  << std::endl;
423  std::cout << "Depth intrinsics:\n"
424  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
425 
426  std::cout << "Infrared intrinsics:\n"
428  << std::endl;
429  std::cout << "Infrared intrinsics:\n"
431  << std::endl;
432 
433  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
434  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
435 
436  time_vector.clear();
437  t_begin = vpTime::measureTimeMs();
438  while (vpTime::measureTimeMs() - t_begin < 10000) {
439  double t = vpTime::measureTimeMs();
440 
441 #ifdef VISP_HAVE_PCL
442  {
443  std::lock_guard<std::mutex> lock(mutex);
444 
445  if (pcl_color) {
446  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud_color,
447  (unsigned char *)infrared.bitmap);
448  } else {
449  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud,
450  (unsigned char *)infrared.bitmap);
451  }
452 
453  update_pointcloud = true;
454  }
455 #else
456  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL,
457  (unsigned char *)infrared.bitmap);
458 #endif
459 
460  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
461 
462  vpDisplay::display(color);
463  vpDisplay::display(depth_color);
464  vpDisplay::display(infrared);
465 
466  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
467 
468  vpDisplay::flush(color);
469  vpDisplay::flush(depth_color);
470  vpDisplay::flush(infrared);
471 
472  time_vector.push_back(vpTime::measureTimeMs() - t);
473  if (vpDisplay::getClick(color, false))
474  break;
475  }
476 
477 #ifdef VISP_HAVE_PCL
478  {
479  std::lock_guard<std::mutex> lock(mutex);
480  cancelled = true;
481  }
482 
483  viewer_thread.join();
484 #endif
485 
486  d1.close(color);
487  d2.close(depth_color);
488  d3.close(infrared);
489  std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector)
490  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
491 
492 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
493  rs.close();
494  config.disable_all_streams();
495  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
496  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
497  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
498  rs.open(config);
499 
500  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
501  cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
502 
503  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
504  cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
505  rs2::colorizer color_map;
506 
507  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
508  cv::Mat mat_infrared(infrared_profile.height(), infrared_profile.width(), CV_8U);
509 
510  time_vector.clear();
511  t_begin = vpTime::measureTimeMs();
512  while (vpTime::measureTimeMs() - t_begin < 10000) {
513  double t = vpTime::measureTimeMs();
514 
515  auto data = pipe.wait_for_frames();
516  frame_to_mat(data.get_color_frame(), mat_color);
517 #if (RS2_API_VERSION >= ((2 * 10000) + (16 * 100) + 0))
518  frame_to_mat(data.get_depth_frame().apply_filter(color_map), mat_depth);
519 #else
520  frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
521 #endif
522  frame_to_mat(data.first(RS2_STREAM_INFRARED), mat_infrared);
523 
524  cv::imshow("OpenCV color", mat_color);
525  cv::imshow("OpenCV depth", mat_depth);
526  cv::imshow("OpenCV infrared", mat_infrared);
527 
528  time_vector.push_back(vpTime::measureTimeMs() - t);
529  if (cv::waitKey(10) == 27)
530  break;
531  }
532 
533  std::cout << "Acquisition3 - Mean time: " << vpMath::getMean(time_vector)
534  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
535 #endif
536 
537 #ifdef VISP_HAVE_PCL
538  //Pointcloud acquisition using std::vector<vpColVector> + visualization
539  //See issue #355
540  ViewerWorker viewer_colvector2(false, mutex);
541  std::thread viewer_colvector_thread2(&ViewerWorker::run, &viewer_colvector2);
542  cancelled = false;
543 
544  rs.close();
545  config.disable_all_streams();
546  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
547  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
548  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
549  rs.open(config);
550 
551  time_vector.clear();
552  t_begin = vpTime::measureTimeMs();
553  while (vpTime::measureTimeMs() - t_begin < 10000) {
554  double t = vpTime::measureTimeMs();
555  rs.acquire(NULL, NULL, &pointcloud_colvector, NULL, NULL);
556 
557  {
558  std::lock_guard<std::mutex> lock(mutex);
559  pointcloud->width = 640;
560  pointcloud->height = 480;
561  pointcloud->points.resize(pointcloud_colvector.size());
562  for (size_t i = 0; i < pointcloud_colvector.size(); i++) {
563  pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
564  pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
565  pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
566  }
567 
568  update_pointcloud = true;
569  }
570 
571  time_vector.push_back(vpTime::measureTimeMs() - t);
572  vpTime::wait(t, 30.0);
573  }
574 
575  {
576  std::lock_guard<std::mutex> lock(mutex);
577  cancelled = true;
578  }
579 
580  viewer_colvector_thread2.join();
581 
582  std::cout << "Acquisition4 - Mean time: " << vpMath::getMean(time_vector)
583  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
584 #endif
585 
586  return EXIT_SUCCESS;
587 }
588 
589 #else
590 int main()
591 {
592 #if !defined(VISP_HAVE_REALSENSE2)
593  std::cout << "Install librealsense2 to make this test work." << std::endl;
594 #endif
595 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
596  std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) "
597  "to make this test work"
598  << std::endl;
599 #endif
600 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
601  std::cout << "X11 or GDI are needed." << std::endl;
602 #endif
603  return 0;
604 }
605 #endif
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:150
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:325
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)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
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:322
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)