Visual Servoing Platform  version 3.0.1 under development (2017-01-22)
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
testRealSense2.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
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Test Intel RealSense acquisition.
32  *
33  *****************************************************************************/
34 
40 #include <iostream>
41 
42 #include <visp3/sensor/vpRealSense.h>
43 #include <visp3/gui/vpDisplayX.h>
44 #include <visp3/gui/vpDisplayGDI.h>
45 #include <visp3/io/vpImageIo.h>
46 #include <visp3/core/vpImageConvert.h>
47 #include <visp3/core/vpMutex.h>
48 #include <visp3/core/vpThread.h>
49 
50 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY)
51 # include <librealsense/rs.h>
52 
53 // Using a thread to display the pointcloud with PCL produces a segfault on OSX
54 #if( ! defined(__APPLE__) && ! defined(__MACH__) ) // Not OSX
55 # if (defined(VISP_HAVE_PTHREAD) || defined(_WIN32)) // Threading available
56 # define USE_THREAD
57 # endif
58 #endif
59 
60 #ifdef VISP_HAVE_PCL
61 # include <pcl/visualization/cloud_viewer.h>
62 # include <pcl/visualization/pcl_visualizer.h>
63 #endif
64 
65 #ifdef VISP_HAVE_PCL
66 #ifdef USE_THREAD
67 // Shared vars
68 typedef enum {
69  capture_waiting,
70  capture_started,
71  capture_stopped
72 } t_CaptureState;
73 t_CaptureState s_capture_state = capture_waiting;
74 vpMutex s_mutex_capture;
75 
76 
77 vpThread::Return displayPointcloudFunction(vpThread::Args args)
78 {
79  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_ = *((pcl::PointCloud<pcl::PointXYZRGB>::Ptr *) args);
80 
81  pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
82  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_);
83  viewer->setBackgroundColor (0, 0, 0);
84  viewer->addCoordinateSystem (1.0);
85  viewer->initCameraParameters ();
86  viewer->setPosition(640+80, 480+80);
87  viewer->setCameraPosition(0,0,-0.5, 0,-1,0);
88  viewer->setSize(640, 480);
89 
90  t_CaptureState capture_state_;
91 
92  do {
93  s_mutex_capture.lock();
94  capture_state_ = s_capture_state;
95  s_mutex_capture.unlock();
96 
97  if (capture_state_ == capture_started) {
98  static bool update = false;
99  if (! update) {
100  viewer->addPointCloud<pcl::PointXYZRGB> (pointcloud_, rgb, "sample cloud");
101  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
102  update = true;
103  }
104  else {
105  viewer->updatePointCloud<pcl::PointXYZRGB> (pointcloud_, rgb, "sample cloud");
106  }
107 
108  viewer->spinOnce (10);
109  }
110  } while(capture_state_ != capture_stopped);
111 
112  std::cout << "End of point cloud display thread" << std::endl;
113  return 0;
114 }
115 #endif
116 #endif
117 
118 #endif
119 
120 
121 int main()
122 {
123 #if defined(VISP_HAVE_REALSENSE) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && ( defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) )
124  try {
125  vpRealSense rs;
126 
127  rs.setEnableStream(rs::stream::color, false);
128  rs.open();
129  if ( rs_get_device_name((const rs_device *) rs.getHandler(), nullptr) != std::string("Intel RealSense SR300") ) {
130  std::cout << "This test file is used to test the Intel RealSense SR300 only." << std::endl;
131  return EXIT_SUCCESS;
132  }
133  rs.close();
134 
135 
136  rs.setEnableStream(rs::stream::color, false);
137  rs.setEnableStream(rs::stream::depth, true);
138  rs.setEnableStream(rs::stream::infrared, false);
139 
140  rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 240, rs::format::z16, 110));
141 
142  rs.open();
143  std::cout << "API version: " << rs_get_api_version(nullptr) << std::endl;
144  std::cout << "Firmware: " << rs_get_device_firmware_version((const rs_device *) rs.getHandler(), nullptr) << std::endl;
145  std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
146 
147  vpImage<uint16_t> depth((unsigned int) rs.getIntrinsics(rs::stream::depth).height, (unsigned int) rs.getIntrinsics(rs::stream::depth).width);
148  vpImage<vpRGBa> I_display_depth(depth.getHeight(), depth.getWidth());
149 
150  std::vector<double> time_vector;
151 
152 #if defined(VISP_HAVE_X11)
153  vpDisplayX dd(I_display_depth, 0, 0, "Depth image");
154 #elif defined(VISP_HAVE_GDI)
155  vpDisplayGDI dd(I_display_depth, 0, 0, "Depth image");
156 #endif
157 
158  //Test depth stream during 10 s
159  double t_begin = vpTime::measureTimeMs();
160  while (true) {
161  double t = vpTime::measureTimeMs();
162  rs.acquire( NULL, (unsigned char *) depth.bitmap, NULL, NULL );
163  vpImageConvert::createDepthHistogram(depth, I_display_depth);
164 
165  vpDisplay::display(I_display_depth);
166  vpDisplay::flush(I_display_depth);
167 
168  if (vpDisplay::getClick(I_display_depth, false)) {
169  break;
170  }
171 
172  time_vector.push_back(vpTime::measureTimeMs() - t);
173  if (vpTime::measureTimeMs() - t_begin >= 10000) {
174  break;
175  }
176  }
177  std::cout << "SR300_DEPTH_Z16_640x240_110FPS - Mean time: " << vpMath::getMean(time_vector) << " ms ; Median time: "
178  << vpMath::getMedian(time_vector) << " ms" << std::endl;
179 
180  dd.close(I_display_depth);
181 
182 
183  rs.setEnableStream(rs::stream::color, true);
184  rs.setEnableStream(rs::stream::depth, false);
185  rs.setEnableStream(rs::stream::infrared, false);
186  rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(1920, 1080, rs::format::rgba8, 30));
187  rs.open();
188 
189  vpImage<vpRGBa> I_color((unsigned int) rs.getIntrinsics(rs::stream::color).height, (unsigned int) rs.getIntrinsics(rs::stream::color).width);
190 
191 #if defined(VISP_HAVE_X11)
192  vpDisplayX dc(I_color, 0, 0, "Color image");
193 #elif defined(VISP_HAVE_GDI)
194  vpDisplayGDI dc(I_color, 0, 0, "Color image");
195 #endif
196 
197  time_vector.clear();
198  //Test color stream during 10 s
199  t_begin = vpTime::measureTimeMs();
200  while (true) {
201  double t = vpTime::measureTimeMs();
202  rs.acquire( (unsigned char *) I_color.bitmap, NULL, NULL, NULL );
203 
204  vpDisplay::display(I_color);
205  vpDisplay::flush(I_color);
206 
207  if (vpDisplay::getClick(I_color, false)) {
208  break;
209  }
210 
211  time_vector.push_back(vpTime::measureTimeMs() - t);
212  if (vpTime::measureTimeMs() - t_begin >= 10000) {
213  break;
214  }
215  }
216  std::cout << "SR300_COLOR_RGBA8_1920x1080_30FPS - Mean time: " << vpMath::getMean(time_vector) << " ms ; Median time: "
217  << vpMath::getMedian(time_vector) << " ms" << std::endl;
218 
219  dc.close(I_color);
220 
221 
222  rs.setEnableStream(rs::stream::color, false);
223  rs.setEnableStream(rs::stream::depth, false);
224  rs.setEnableStream(rs::stream::infrared, true);
225  rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y16, 200));
226  rs.open();
227 
228  vpImage<uint16_t> infrared((unsigned int) rs.getIntrinsics(rs::stream::infrared).height, (unsigned int) rs.getIntrinsics(rs::stream::infrared).width);
229  vpImage<unsigned char> I_display_infrared(infrared.getHeight(), infrared.getWidth());
230 
231 #if defined(VISP_HAVE_X11)
232  vpDisplayX di(I_display_infrared, 0, 0, "Infrared image");
233 #elif defined(VISP_HAVE_GDI)
234  vpDisplayGDI di(I_display_infrared, 0, 0, "Infrared image");
235 #endif
236 
237  time_vector.clear();
238  //Test infrared stream during 10 s
239  t_begin = vpTime::measureTimeMs();
240  while (true) {
241  double t = vpTime::measureTimeMs();
242  rs.acquire( NULL, NULL, NULL, (unsigned char *) infrared.bitmap );
243  vpImageConvert::convert(infrared, I_display_infrared);
244 
245  vpDisplay::display(I_display_infrared);
246  vpDisplay::flush(I_display_infrared);
247 
248  if (vpDisplay::getClick(I_display_infrared, false)) {
249  break;
250  }
251 
252  time_vector.push_back(vpTime::measureTimeMs() - t);
253  if (vpTime::measureTimeMs() - t_begin >= 10000) {
254  break;
255  }
256  }
257  std::cout << "SR300_INFRARED_Y16_640x480_200FPS - Mean time: " << vpMath::getMean(time_vector) << " ms ; Median time: "
258  << vpMath::getMedian(time_vector) << " ms" << std::endl;
259 
260  di.close(I_display_infrared);
261 
262 
263  rs.setEnableStream(rs::stream::color, false);
264  rs.setEnableStream(rs::stream::depth, true);
265  rs.setEnableStream(rs::stream::infrared, false);
266  rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60));
267  rs.open();
268 
269  depth.resize( (unsigned int) rs.getIntrinsics(rs::stream::depth).height, (unsigned int) rs.getIntrinsics(rs::stream::depth).width );
270  I_display_depth.resize( depth.getHeight(), depth.getWidth() );
271 
272 #if defined(VISP_HAVE_X11)
273  dd.init(I_display_depth, 0, 0, "Depth image");
274 #elif defined(VISP_HAVE_GDI)
275  dd.init(I_display_depth, 0, 0, "Depth image");
276 #endif
277 
278  time_vector.clear();
279  //Test depth stream during 10 s
280  t_begin = vpTime::measureTimeMs();
281  while (true) {
282  double t = vpTime::measureTimeMs();
283  rs.acquire( NULL, (unsigned char *) depth.bitmap, NULL, NULL );
284  vpImageConvert::createDepthHistogram(depth, I_display_depth);
285 
286  vpDisplay::display(I_display_depth);
287  vpDisplay::flush(I_display_depth);
288 
289  if (vpDisplay::getClick(I_display_depth, false)) {
290  break;
291  }
292 
293  time_vector.push_back(vpTime::measureTimeMs() - t);
294  if (vpTime::measureTimeMs() - t_begin >= 10000) {
295  break;
296  }
297  }
298  std::cout << "SR300_DEPTH_Z16_640x480_60FPS - Mean time: " << vpMath::getMean(time_vector) << " ms ; Median time: "
299  << vpMath::getMedian(time_vector) << " ms" << std::endl;
300 
301  dd.close(I_display_depth);
302 
303 
304  rs.setEnableStream(rs::stream::color, false);
305  rs.setEnableStream(rs::stream::depth, true);
306  rs.setEnableStream(rs::stream::infrared, true);
307  rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60));
308  rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60));
309  rs.open();
310 
311 #if defined(VISP_HAVE_X11)
312  dd.init(I_display_depth, 0, 0, "Depth image");
313  di.init(I_display_infrared, (int) I_display_depth.getWidth(), 0, "Infrared image");
314 #elif defined(VISP_HAVE_GDI)
315  dd.init(I_display_depth, 0, 0, "Depth image");
316  di.init(I_display_infrared, I_display_depth.getWidth(), 0, "Infrared image");
317 #endif
318 
319  time_vector.clear();
320  //Test depth stream during 10 s
321  t_begin = vpTime::measureTimeMs();
322  while (true) {
323  double t = vpTime::measureTimeMs();
324  rs.acquire( NULL, (unsigned char *) depth.bitmap, NULL, (unsigned char *) I_display_infrared.bitmap );
325  vpImageConvert::createDepthHistogram(depth, I_display_depth);
326 
327  vpDisplay::display(I_display_depth);
328  vpDisplay::display(I_display_infrared);
329  vpDisplay::flush(I_display_depth);
330  vpDisplay::flush(I_display_infrared);
331 
332  if (vpDisplay::getClick(I_display_depth, false) || vpDisplay::getClick(I_display_infrared, false)) {
333  break;
334  }
335 
336  time_vector.push_back(vpTime::measureTimeMs() - t);
337  if (vpTime::measureTimeMs() - t_begin >= 10000) {
338  break;
339  }
340  }
341  std::cout << "SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS - Mean time: " << vpMath::getMean(time_vector)
342  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
343 
344 
345  dd.close(I_display_depth);
346  di.close(I_display_infrared);
347 
348 
349 
350 #ifdef VISP_HAVE_PCL
351  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZRGB>);
352 
353 #ifdef USE_THREAD
354  vpThread thread_display_pointcloud(displayPointcloudFunction, (vpThread::Args)&pointcloud);
355 #else
356  pcl::visualization::PCLVisualizer::Ptr viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
357  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud);
358  viewer->setBackgroundColor (0, 0, 0);
359  viewer->addCoordinateSystem (1.0);
360  viewer->initCameraParameters ();
361  viewer->setCameraPosition(0,0,-0.5, 0,-1,0);
362  viewer->setSize(640, 480);
363 #endif
364 
365  rs.setEnableStream(rs::stream::color, true);
366  rs.setEnableStream(rs::stream::depth, true);
367  rs.setEnableStream(rs::stream::infrared, true);
368  rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 60));
369  rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 60));
370  rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 60));
371  rs.open();
372 
373  I_color.resize(480, 640);
374 
375 #if defined(VISP_HAVE_X11)
376  dc.init(I_color, 0, 0, "Color image");
377  dd.init(I_display_depth, 0, (int) I_color.getHeight()+80, "Depth image");
378  di.init(I_display_infrared, (int) I_display_depth.getWidth(), 0, "Infrared image");
379 #elif defined(VISP_HAVE_GDI)
380  dc.init(I_color, 0, 0, "Color image");
381  dd.init(I_display_depth, 0, (int) I_color.getHeight()+80, "Depth image");
382  di.init(I_display_infrared, (int) I_display_depth.getWidth(), 0, "Infrared image");
383 #endif
384 
385  time_vector.clear();
386  //Test depth stream during 10 s
387  t_begin = vpTime::measureTimeMs();
388  while (true) {
389  double t = vpTime::measureTimeMs();
390  rs.acquire( (unsigned char *) I_color.bitmap, (unsigned char *) depth.bitmap, NULL, pointcloud, (unsigned char *) I_display_infrared.bitmap );
391  vpImageConvert::createDepthHistogram(depth, I_display_depth);
392 
393 #ifdef VISP_HAVE_PCL
394 #ifdef USE_THREAD
395  {
396  vpMutex::vpScopedLock lock(s_mutex_capture);
397  s_capture_state = capture_started;
398  }
399 #else
400  static bool update = false;
401  if (! update) {
402  viewer->addPointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
403  viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
404  viewer->setPosition( (int) I_color.getWidth()+80, (int) I_color.getHeight()+80) ;
405  update = true;
406  }
407  else {
408  viewer->updatePointCloud<pcl::PointXYZRGB> (pointcloud, rgb, "sample cloud");
409  }
410 
411  viewer->spinOnce (10);
412 #endif
413 #endif
414 
415  vpDisplay::display(I_color);
416  vpDisplay::display(I_display_depth);
417  vpDisplay::display(I_display_infrared);
418  vpDisplay::flush(I_color);
419  vpDisplay::flush(I_display_depth);
420  vpDisplay::flush(I_display_infrared);
421 
422  if (vpDisplay::getClick(I_color, false) || vpDisplay::getClick(I_display_depth, false) || vpDisplay::getClick(I_display_infrared, false)) {
423  break;
424  }
425 
426  time_vector.push_back(vpTime::measureTimeMs() - t);
427  if (vpTime::measureTimeMs() - t_begin >= 10000) {
428  break;
429  }
430  }
431  std::cout << "SR300_COLOR_RGBA8_640x480_60FPS + SR300_DEPTH_Z16_640x480_60FPS + SR300_INFRARED_Y8_640x480_60FPS - Mean time: " << vpMath::getMean(time_vector)
432  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
433 
434 #ifdef VISP_HAVE_PCL
435 #ifdef USE_THREAD
436  {
437  vpMutex::vpScopedLock lock(s_mutex_capture);
438  s_capture_state = capture_stopped;
439  }
440 #endif
441 #endif
442 
443  dc.close(I_color);
444  dd.close(I_display_depth);
445  di.close(I_display_infrared);
446 
447 #endif
448 
449 
450  //Color stream aligned to depth
451  rs.setEnableStream(rs::stream::color, true);
452  rs.setEnableStream(rs::stream::depth, true);
453  rs.setEnableStream(rs::stream::infrared, false);
454  rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::rgba8, 30));
455  rs.setStreamSettings(rs::stream::depth, vpRealSense::vpRsStreamParams(640, 480, rs::format::z16, 30));
456  rs.open();
457 
458  dc.init(I_color, 0, 0, "Color aligned to depth");
459  di.init(I_display_depth, (int) I_color.getWidth(), 0, "Depth image");
460 
461  t_begin = vpTime::measureTimeMs();
462  while (true) {
463  double t = vpTime::measureTimeMs();
464  rs.acquire( (unsigned char *) I_color.bitmap, (unsigned char *) depth.bitmap, NULL, NULL, NULL, rs::stream::color_aligned_to_depth );
465  vpImageConvert::createDepthHistogram(depth, I_display_depth);
466 
467  vpDisplay::display(I_color);
468  vpDisplay::display(I_display_depth);
469  vpDisplay::flush(I_color);
470  vpDisplay::flush(I_display_depth);
471 
472  if (vpDisplay::getClick(I_color, false) || vpDisplay::getClick(I_display_depth, false)) {
473  break;
474  }
475 
476  time_vector.push_back(vpTime::measureTimeMs() - t);
477  if (vpTime::measureTimeMs() - t_begin >= 10000) {
478  break;
479  }
480  }
481 
482  dc.close(I_color);
483  dd.close(I_display_depth);
484 
485 
486  //Depth stream aligned to color
487  dc.init(I_color, 0, 0, "Color image");
488  di.init(I_display_depth, (int) I_color.getWidth(), 0, "Depth aligned to color");
489 
490  t_begin = vpTime::measureTimeMs();
491  while (true) {
492  double t = vpTime::measureTimeMs();
493  rs.acquire( (unsigned char *) I_color.bitmap, (unsigned char *) depth.bitmap, NULL, NULL, NULL, rs::stream::color, rs::stream::depth_aligned_to_color );
494  vpImageConvert::createDepthHistogram(depth, I_display_depth);
495 
496  vpDisplay::display(I_color);
497  vpDisplay::display(I_display_depth);
498  vpDisplay::flush(I_color);
499  vpDisplay::flush(I_display_depth);
500 
501  if (vpDisplay::getClick(I_color, false) || vpDisplay::getClick(I_display_depth, false)) {
502  break;
503  }
504 
505  time_vector.push_back(vpTime::measureTimeMs() - t);
506  if (vpTime::measureTimeMs() - t_begin >= 10000) {
507  break;
508  }
509  }
510 
511  dc.close(I_color);
512  dd.close(I_display_depth);
513 
514 
515 
516 #if VISP_HAVE_OPENCV_VERSION >= 0x020409
517  rs.setEnableStream(rs::stream::color, true);
518  rs.setEnableStream(rs::stream::depth, false);
519  rs.setEnableStream(rs::stream::infrared, true);
520  rs.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(640, 480, rs::format::bgr8, 60));
521  rs.setStreamSettings(rs::stream::infrared, vpRealSense::vpRsStreamParams(640, 480, rs::format::y8, 200));
522  rs.open();
523 
524  cv::Mat color_mat(480, 640, CV_8UC3);
525  cv::Mat infrared_mat(480, 640, CV_8U);
526 
527  t_begin = vpTime::measureTimeMs();
528  while (true) {
529  double t = vpTime::measureTimeMs();
530  rs.acquire( color_mat.data, NULL, NULL, infrared_mat.data );
531 
532  cv::imshow("Color mat", color_mat);
533  cv::imshow("Infrared mat", infrared_mat);
534  char c = cv::waitKey(10);
535  if (c == 27) {
536  break;
537  }
538 
539  time_vector.push_back(vpTime::measureTimeMs() - t);
540  if (vpTime::measureTimeMs() - t_begin >= 10000) {
541  break;
542  }
543  }
544 #endif
545 
546  } catch(const vpException &e) {
547  std::cerr << "RealSense error " << e.what() << std::endl;
548  } catch(const rs::error & e) {
549  std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "): " << e.what() << std::endl;
550  } catch(const std::exception & e) {
551  std::cerr << e.what() << std::endl;
552  }
553 
554 #elif !defined(VISP_HAVE_REALSENSE)
555  std::cout << "Install RealSense SDK to make this test working. X11 or GDI are needed also." << std::endl;
556 #elif !defined(VISP_HAVE_CPP11_COMPATIBILITY)
557  std::cout << "Build ViSP with c++11 compiler flag (cmake -DUSE_CPP11=ON) to make this test working" << std::endl;
558 #endif
559  return EXIT_SUCCESS;
560 }
Class that allows protection by mutex.
Definition: vpMutex.h:163
void lock()
Definition: vpMutex.h:90
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void * Return
Definition: vpThread.h:36
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:519
rs::device * getHandler() const
Get access to device handler.
Definition: vpRealSense.h:355
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:217
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
void unlock()
Definition: vpMutex.h:106
Define the X11 console to display images.
Definition: vpDisplayX.h:153
error that can be emited by ViSP classes.
Definition: vpException.h:73
void acquire(std::vector< vpColVector > &pointcloud)
static void flush(const vpImage< unsigned char > &I)
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:93
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:197
const char * what() const
void * Args
Definition: vpThread.h:35
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)
Definition of the vpImage class member functions.
Definition: vpImage.h:114
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)