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