Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
testRealSense_R200.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.
33  *
34  *****************************************************************************/
35 
41 #include <iostream>
42 
43 #include <visp3/core/vpImageConvert.h>
44 #include <visp3/gui/vpDisplayGDI.h>
45 #include <visp3/gui/vpDisplayX.h>
46 #include <visp3/io/vpImageIo.h>
47 #include <visp3/sensor/vpRealSense.h>
48 
49 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
50  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
51 #include <mutex>
52 #include <thread>
53 
54 #ifdef VISP_HAVE_PCL
55 #include <pcl/visualization/cloud_viewer.h>
56 #include <pcl/visualization/pcl_visualizer.h>
57 #endif
58 
59 namespace
60 {
61 
62 #ifdef VISP_HAVE_PCL
63 // Global variables
64 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
65 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
66 bool cancelled = false, update_pointcloud = false;
67 
68 class ViewerWorker
69 {
70 public:
71  explicit ViewerWorker(const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
72 
73  void run()
74  {
75  std::string date = vpTime::getDateTime();
76  pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
77  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
78  pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
79  pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
80 
81  viewer->setBackgroundColor(0, 0, 0);
82  viewer->initCameraParameters();
83  viewer->setPosition(640 + 80, 480 + 80);
84  viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
85  viewer->setSize(640, 480);
86 
87  bool init = true;
88  bool local_update = false, local_cancelled = false;
89  while (!local_cancelled) {
90  {
91  std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
92 
93  if (lock.owns_lock()) {
94  local_update = update_pointcloud;
95  update_pointcloud = false;
96  local_cancelled = cancelled;
97 
98  if (local_update) {
99  if (m_colorMode) {
100  local_pointcloud_color = pointcloud_color->makeShared();
101  } else {
102  local_pointcloud = pointcloud->makeShared();
103  }
104  }
105  }
106  }
107 
108  if (local_update && !local_cancelled) {
109  local_update = false;
110 
111  if (init) {
112  if (m_colorMode) {
113  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
114  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
115  "RGB sample cloud");
116  } else {
117  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
118  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
119  }
120  init = false;
121  } else {
122  if (m_colorMode) {
123  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
124  } else {
125  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
126  }
127  }
128  }
129 
130  viewer->spinOnce(5);
131  }
132 
133  std::cout << "End of point cloud display thread" << std::endl;
134  }
135 
136 private:
137  bool m_colorMode;
138  std::mutex &m_mutex;
139 };
140 #endif //#ifdef VISP_HAVE_PCL
141 
142 void test_R200(vpRealSense &rs, const std::map<rs::stream, bool> &enables,
143  const std::map<rs::stream, vpRealSense::vpRsStreamParams> &params,
144  const std::map<rs::option, double> &options, const std::string &title,
145  const bool depth_color_visualization = false, const rs::stream &color_stream = rs::stream::color,
146  const rs::stream &depth_stream = rs::stream::depth,
147  const rs::stream &infrared2_stream = rs::stream::infrared2, bool display_pcl = false,
148  bool pcl_color = false)
149 {
150  std::cout << std::endl;
151 
152  std::map<rs::stream, bool>::const_iterator it_enable;
153  std::map<rs::stream, vpRealSense::vpRsStreamParams>::const_iterator it_param;
154 
155  for (it_enable = enables.begin(), it_param = params.begin(); it_enable != enables.end(); ++it_enable) {
156  rs.setEnableStream(it_enable->first, it_enable->second);
157 
158  if (it_enable->second) {
159  it_param = params.find(it_enable->first);
160 
161  if (it_param != params.end()) {
162  rs.setStreamSettings(it_param->first, it_param->second);
163  }
164  }
165  }
166 
167  rs.open();
168 
169  vpImage<uint16_t> depth;
170  vpImage<unsigned char> I_depth;
171  vpImage<vpRGBa> I_depth_color;
172 
173  vpImage<vpRGBa> I_color;
174  vpImage<uint16_t> infrared, infrared2;
175  vpImage<unsigned char> I_infrared, I_infrared2;
176 
177  bool direct_infrared_conversion = false;
178  for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
179  if (it_enable->second) {
180  switch (it_enable->first) {
181  case rs::stream::color:
182  I_color.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
183  (unsigned int)rs.getIntrinsics(it_enable->first).width);
184  break;
185 
186  case rs::stream::depth:
187  depth.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
188  (unsigned int)rs.getIntrinsics(it_enable->first).width);
189  I_depth.init(depth.getHeight(), depth.getWidth());
190  I_depth_color.init(depth.getHeight(), depth.getWidth());
191  break;
192 
193  case rs::stream::infrared:
194  infrared.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
195  (unsigned int)rs.getIntrinsics(it_enable->first).width);
196  I_infrared.init(infrared.getHeight(), infrared.getWidth());
197 
198  it_param = params.find(it_enable->first);
199  if (it_param != params.end()) {
200  direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
201  }
202  break;
203 
204  case rs::stream::infrared2:
205  infrared2.init((unsigned int)rs.getIntrinsics(it_enable->first).height,
206  (unsigned int)rs.getIntrinsics(it_enable->first).width);
207  I_infrared2.init(infrared.getHeight(), infrared.getWidth());
208 
209  it_param = params.find(it_enable->first);
210  if (it_param != params.end()) {
211  direct_infrared_conversion = it_param->second.m_streamFormat == rs::format::y8;
212  }
213  break;
214 
215  default:
216  break;
217  }
218  }
219  }
220 
221 #if defined(VISP_HAVE_X11)
222  vpDisplayX dc, dd, di, di2;
223 #elif defined(VISP_HAVE_GDI)
224  vpDisplayGDI dc, dd, di, di2;
225 #endif
226 
227  for (it_enable = enables.begin(); it_enable != enables.end(); ++it_enable) {
228  if (it_enable->second) {
229  switch (it_enable->first) {
230  case rs::stream::color:
231  dc.init(I_color, 0, 0, "Color frame");
232  break;
233 
234  case rs::stream::depth:
235  if (depth_color_visualization) {
236  dd.init(I_depth_color, (int)I_color.getWidth() + 80, 0, "Depth frame");
237  } else {
238  dd.init(I_depth, (int)I_color.getWidth() + 80, 0, "Depth frame");
239  }
240  break;
241 
242  case rs::stream::infrared:
243  di.init(I_infrared, 0, (int)(std::max)(I_color.getHeight(), I_depth.getHeight()) + 30, "Infrared frame");
244  break;
245 
246  case rs::stream::infrared2:
247  di2.init(I_infrared2, (int)I_infrared.getWidth(),
248  (int)(std::max)(I_color.getHeight(), I_depth.getHeight()) + 30, "Infrared2 frame");
249  break;
250 
251  default:
252  break;
253  }
254  }
255  }
256 
257  std::cout << "direct_infrared_conversion=" << direct_infrared_conversion << std::endl;
258 
259 #ifdef VISP_HAVE_PCL
260  std::mutex mutex;
261  ViewerWorker viewer(pcl_color, mutex);
262  std::thread viewer_thread;
263 
264  if (display_pcl) {
265  viewer_thread = std::thread(&ViewerWorker::run, &viewer);
266  }
267 #else
268  display_pcl = false;
269 #endif
270 
271  rs::device *dev = rs.getHandler();
272 
273  // Test stream acquisition during 10 s
274  std::vector<double> time_vector;
275  double t_begin = vpTime::measureTimeMs();
276  while (true) {
277  double t = vpTime::measureTimeMs();
278 
279  for (std::map<rs::option, double>::const_iterator it = options.begin(); it != options.end(); ++it) {
280  dev->set_option(it->first, it->second);
281  }
282 
283  if (display_pcl) {
284 #ifdef VISP_HAVE_PCL
285  std::lock_guard<std::mutex> lock(mutex);
286 
287  if (direct_infrared_conversion) {
288  if (pcl_color) {
289  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
290  (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream,
291  depth_stream, rs::stream::infrared, infrared2_stream);
292  } else {
293  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud,
294  (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream,
295  depth_stream, rs::stream::infrared, infrared2_stream);
296  }
297  } else {
298  if (pcl_color) {
299  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
300  (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream,
301  rs::stream::infrared, infrared2_stream);
302  } else {
303  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud,
304  (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream,
305  rs::stream::infrared, infrared2_stream);
306  }
307 
308  vpImageConvert::convert(infrared, I_infrared);
309  vpImageConvert::convert(infrared2, I_infrared2);
310  }
311 
312  update_pointcloud = true;
313 #endif
314  } else {
315  if (direct_infrared_conversion) {
316  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL,
317  (unsigned char *)I_infrared.bitmap, (unsigned char *)I_infrared2.bitmap, color_stream, depth_stream,
318  rs::stream::infrared, infrared2_stream);
319  } else {
320  rs.acquire((unsigned char *)I_color.bitmap, (unsigned char *)depth.bitmap, NULL,
321  (unsigned char *)infrared.bitmap, (unsigned char *)infrared2.bitmap, color_stream, depth_stream,
322  rs::stream::infrared, infrared2_stream);
323  vpImageConvert::convert(infrared, I_infrared);
324  vpImageConvert::convert(infrared2, I_infrared2);
325  }
326  }
327 
328  if (depth_color_visualization) {
329  vpImageConvert::createDepthHistogram(depth, I_depth_color);
330  } else {
331  vpImageConvert::createDepthHistogram(depth, I_depth);
332  }
333 
334  vpDisplay::display(I_color);
335  if (depth_color_visualization) {
336  vpDisplay::display(I_depth_color);
337  } else {
338  vpDisplay::display(I_depth);
339  }
340  vpDisplay::display(I_infrared);
341  vpDisplay::display(I_infrared2);
342 
343  vpDisplay::flush(I_color);
344  if (depth_color_visualization) {
345  vpDisplay::flush(I_depth_color);
346  } else {
347  vpDisplay::flush(I_depth);
348  }
349  vpDisplay::flush(I_infrared);
350  vpDisplay::flush(I_infrared2);
351 
352  if (vpDisplay::getClick(I_color, false) ||
353  (depth_color_visualization ? vpDisplay::getClick(I_depth_color, false) : vpDisplay::getClick(I_depth, false)) ||
354  vpDisplay::getClick(I_infrared, false) || vpDisplay::getClick(I_infrared2, false)) {
355  break;
356  }
357 
358  time_vector.push_back(vpTime::measureTimeMs() - t);
359  if (vpTime::measureTimeMs() - t_begin >= 10000) {
360  break;
361  }
362  }
363 
364  if (display_pcl) {
365 #ifdef VISP_HAVE_PCL
366  {
367  std::lock_guard<std::mutex> lock(mutex);
368  cancelled = true;
369  }
370 
371  viewer_thread.join();
372 #endif
373  }
374 
375  std::cout << title << " - Mean time: " << vpMath::getMean(time_vector)
376  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
377 
378  rs.close();
379 }
380 
381 } // namespace
382 
383 int main(int argc, char *argv[])
384 {
385  try {
386  vpRealSense rs;
387 
388  rs.setEnableStream(rs::stream::color, false);
389  rs.open();
390  if (rs_get_device_name((const rs_device *)rs.getHandler(), nullptr) != std::string("Intel RealSense R200")) {
391  std::cout << "This test file is used to test the Intel RealSense R200 only." << std::endl;
392  return EXIT_SUCCESS;
393  }
394 
395  std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl;
396  std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *)rs.getHandler(), nullptr)
397  << std::endl;
398  std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
399 
400  rs.close();
401 
402  std::map<rs::stream, bool> enables;
403  std::map<rs::stream, vpRealSense::vpRsStreamParams> params;
404  std::map<rs::option, double> options;
405 
406  enables[rs::stream::color] = false;
407  enables[rs::stream::depth] = true;
408  enables[rs::stream::infrared] = false;
409  enables[rs::stream::infrared2] = false;
410 
411  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90);
412 
413  options[rs::option::r200_lr_auto_exposure_enabled] = 1;
414 
415  test_R200(rs, enables, params, options, "R200_DEPTH_Z16_640x480_90FPS + r200_lr_auto_exposure_enabled", true);
416 
417  enables[rs::stream::color] = false;
418  enables[rs::stream::depth] = true;
419  enables[rs::stream::infrared] = true;
420  enables[rs::stream::infrared2] = true;
421 
422  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90);
423  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
424  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
425 
426  options[rs::option::r200_lr_auto_exposure_enabled] = 0;
427  options[rs::option::r200_emitter_enabled] = 0;
428 
429  test_R200(rs, enables, params, options,
430  "R200_DEPTH_Z16_640x480_90FPS + R200_INFRARED_Y8_640x480_90FPS "
431  "+ R200_INFRARED2_Y8_640x480_90FPS + "
432  "!r200_lr_auto_exposure_enabled + !r200_emitter_enabled",
433  true);
434 
435  enables[rs::stream::color] = false;
436  enables[rs::stream::depth] = true;
437  enables[rs::stream::infrared] = true;
438  enables[rs::stream::infrared2] = true;
439 
440  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90);
441  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90);
442  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 90);
443 
444  options[rs::option::r200_lr_auto_exposure_enabled] = 1;
445  options[rs::option::r200_emitter_enabled] = 1;
446 
447  test_R200(rs, enables, params, options,
448  "R200_DEPTH_Z16_628x468_90FPS + "
449  "R200_INFRARED_Y16_640x480_90FPS + "
450  "R200_INFRARED2_Y16_640x480_90FPS");
451 
452  enables[rs::stream::color] = false;
453  enables[rs::stream::depth] = true;
454  enables[rs::stream::infrared] = true;
455  enables[rs::stream::infrared2] = true;
456 
457  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(628, 468, rs::format::z16, 90);
458  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
459  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
460 
461  options.clear();
462 
463  test_R200(rs, enables, params, options,
464  "R200_DEPTH_Z16_628x468_90FPS + R200_INFRARED_Y8_640x480_90FPS "
465  "+ R200_INFRARED2_Y8_640x480_90FPS");
466 
467  enables[rs::stream::color] = true;
468  enables[rs::stream::depth] = true;
469  enables[rs::stream::infrared] = true;
470  enables[rs::stream::infrared2] = true;
471 
472  params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30);
473  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 90);
474  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
475  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 90);
476 
477  test_R200(rs, enables, params, options,
478  "R200_COLOR_RGBA8_640x480_30FPS + R200_DEPTH_Z16_628x468_90FPS "
479  "+ R200_INFRARED_Y8_640x480_90FPS + "
480  "R200_INFRARED2_Y8_640x480_90FPS",
481  true);
482 
483  enables[rs::stream::color] = true;
484  enables[rs::stream::depth] = false;
485  enables[rs::stream::infrared] = false;
486  enables[rs::stream::infrared2] = false;
487 
488  params[rs::stream::color] = vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30);
489 
490  test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_1920x1080_30FPS");
491 
492  enables[rs::stream::color] = true;
493  enables[rs::stream::depth] = false;
494  enables[rs::stream::infrared] = false;
495  enables[rs::stream::infrared2] = false;
496 
497  params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60);
498  test_R200(rs, enables, params, options, "R200_COLOR_RGBA8_640x480_60FPS");
499 
500  enables[rs::stream::color] = true;
501  enables[rs::stream::depth] = true;
502  enables[rs::stream::infrared] = true;
503  enables[rs::stream::infrared2] = true;
504 
505  params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60);
506  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60);
507  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
508  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
509 
510  // depth == 0 ; color == 1 ; infrared2 == 3 ; rectified_color == 6 ;
511  // color_aligned_to_depth == 7 ; infrared2_aligned_to_depth == 8 ;
512  // depth_aligned_to_color == 9 ; depth_aligned_to_rectified_color == 10 ;
513  // depth_aligned_to_infrared2 == 11 argv[2] <==> color stream
514  rs::stream color_stream = argc > 2 ? (rs::stream)atoi(argv[2]) : rs::stream::color_aligned_to_depth;
515  std::cout << "\ncolor_stream: " << color_stream << std::endl;
516  // argv[3] <==> depth stream
517  rs::stream depth_stream = argc > 3 ? (rs::stream)atoi(argv[3]) : rs::stream::depth_aligned_to_rectified_color;
518  std::cout << "depth_stream: " << depth_stream << std::endl;
519  // argv[4] <==> depth stream
520  rs::stream infrared2_stream = argc > 4 ? (rs::stream)atoi(argv[4]) : rs::stream::infrared2_aligned_to_depth;
521  std::cout << "infrared2_stream: " << infrared2_stream << std::endl;
522 
523  test_R200(rs, enables, params, options,
524  "R200_COLOR_ALIGNED_TO_DEPTH_RGBA8_640x480_60FPS + "
525  "R200_DEPTH_ALIGNED_TO_RECTIFIED_COLOR_Z16_640x480_60FPS + "
526  "R200_INFRARED_Y8_640x480_60FPS + "
527  "R200_INFRARED2_ALIGNED_TO_DEPTH_Y8_640x480_60FPS",
528  true, color_stream, depth_stream, infrared2_stream);
529 
530 #if (!defined(__APPLE__) && !defined(__MACH__)) // Not OSX, since viewer->spinOnce (10); produces a
531  // segfault on OSX
532 
533  enables[rs::stream::color] = true;
534  enables[rs::stream::depth] = true;
535  enables[rs::stream::infrared] = true;
536  enables[rs::stream::infrared2] = true;
537 
538  params[rs::stream::color] = vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60);
539  params[rs::stream::depth] = vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60);
540  params[rs::stream::infrared] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
541  params[rs::stream::infrared2] = vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60);
542 
543  // Cannot render two pcl::visualization::PCLVisualizer so use an arg
544  // option to switch between B&W and color point cloud rendering until a
545  // solution is found
546  test_R200(rs, enables, params, options,
547  "R200_COLOR_RGBA8_640x480_60FPS + R200_DEPTH_Z16_640x480_60FPS + "
548  "R200_INFRARED_Y8_640x480_60FPS + R200_INFRARED2_Y8_640x480_60FPS",
549  false, rs::stream::color, rs::stream::depth, rs::stream::infrared2, true,
550  (argc > 1 ? (bool)(atoi(argv[1]) > 0) : false));
551 #endif
552  } catch (const vpException &e) {
553  std::cerr << "RealSense error " << e.what() << std::endl;
554  } catch (const rs::error &e) {
555  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args()
556  << "): " << e.what() << std::endl;
557  } catch (const std::exception &e) {
558  std::cerr << e.what() << std::endl;
559  }
560 
561  return EXIT_SUCCESS;
562 }
563 
564 #else
565 int main()
566 {
567 #if !defined(VISP_HAVE_REALSENSE)
568  std::cout << "Install RealSense SDK to make this test working. X11 or GDI "
569  "are needed also."
570  << std::endl;
571 #elif !defined(VISP_HAVE_CPP11_COMPATIBILITY)
572  std::cout << "Build ViSP with c++11 compiler flag (cmake -DUSE_CPP11=ON) "
573  "to make this test working"
574  << std::endl;
575 #elif !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
576  std::cout << "X11 or GDI are needed!" << std::endl;
577 #endif
578  return EXIT_SUCCESS;
579 }
580 #endif
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
unsigned int getWidth() const
Definition: vpImage.h:239
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
void init(unsigned int height, unsigned int width)
Set the size of the image.
Definition: vpImage.h:660
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:395
Type * bitmap
points toward the bitmap
Definition: vpImage.h:133
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
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
error that can be emited by ViSP classes.
Definition: vpException.h:71
void acquire(std::vector< vpColVector > &pointcloud)
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 double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:202
const char * what() const
static void display(const vpImage< unsigned char > &I)
rs::intrinsics getIntrinsics(const rs::stream &stream) const
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
void setEnableStream(const rs::stream &stream, const bool status)
unsigned int getHeight() const
Definition: vpImage.h:178
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
Definition of the vpImage class member functions.
Definition: vpImage.h:116
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)