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