Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
testRealSense2_D435.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Test Intel RealSense acquisition with librealsense2.
33  *
34  *****************************************************************************/
40 #include <iostream>
41 
42 #include <visp3/core/vpConfig.h>
43 
44 #if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
45  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
46 
47 #include <visp3/core/vpImage.h>
48 #include <visp3/core/vpImageConvert.h>
49 #include <visp3/gui/vpDisplayGDI.h>
50 #include <visp3/gui/vpDisplayX.h>
51 #include <visp3/sensor/vpRealSense2.h>
52 
53 #ifdef VISP_HAVE_PCL
54 #include <pcl/visualization/cloud_viewer.h>
55 #include <pcl/visualization/pcl_visualizer.h>
56 #include <thread>
57 #include <mutex>
58 #endif
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 #ifdef VISP_HAVE_PCL
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(const 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  } else {
107  local_pointcloud = pointcloud->makeShared();
108  }
109  }
110  }
111  }
112 
113  if (local_update && !local_cancelled) {
114  local_update = false;
115 
116  if (init) {
117  if (m_colorMode) {
118  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
119  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
120  "RGB sample cloud");
121  } else {
122  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
123  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
124  }
125  init = false;
126  } else {
127  if (m_colorMode) {
128  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
129  } else {
130  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
131  }
132  }
133  }
134 
135  viewer->spinOnce(5);
136  }
137 
138  std::cout << "End of point cloud display thread" << std::endl;
139  }
140 
141 private:
142  bool m_colorMode;
143  std::mutex &m_mutex;
144 };
145 
146 void getPointcloud(const rs2::depth_frame &depth_frame, std::vector<vpColVector> &pointcloud)
147 {
148  auto vf = depth_frame.as<rs2::video_frame>();
149  const int width = vf.get_width();
150  const int height = vf.get_height();
151  pointcloud.resize((size_t)(width * height));
152 
153  rs2::pointcloud pc;
154  rs2::points points = pc.calculate(depth_frame);
155  auto vertices = points.get_vertices();
156  vpColVector v(4);
157  for (size_t i = 0; i < points.size(); i++) {
158  if (vertices[i].z) {
159  v[0] = vertices[i].x;
160  v[1] = vertices[i].y;
161  v[2] = vertices[i].z;
162  v[3] = 1.0;
163  } else {
164  v[0] = 0.0;
165  v[1] = 0.0;
166  v[2] = 0.0;
167  v[3] = 1.0;
168  }
169 
170  pointcloud[i] = v;
171  }
172 }
173 #endif
174 
175 void getNativeFrame(const rs2::frame &frame, unsigned char *const data)
176 {
177  auto vf = frame.as<rs2::video_frame>();
178  int size = vf.get_width() * vf.get_height();
179 
180  switch (frame.get_profile().format()) {
181  case RS2_FORMAT_RGB8:
182  case RS2_FORMAT_BGR8:
183  memcpy(data, (void *)frame.get_data(), size * 3);
184  break;
185 
186  case RS2_FORMAT_RGBA8:
187  case RS2_FORMAT_BGRA8:
188  memcpy(data, (void *)frame.get_data(), size * 4);
189  break;
190 
191  case RS2_FORMAT_Y16:
192  case RS2_FORMAT_Z16:
193  memcpy(data, (unsigned char *)frame.get_data(), size * 2);
194  break;
195 
196  case RS2_FORMAT_Y8:
197  memcpy(data, (unsigned char *)frame.get_data(), size);
198  break;
199 
200  default:
201  break;
202  }
203 }
204 
205 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
206 void frame_to_mat(const rs2::frame &f, cv::Mat &img)
207 {
208  auto vf = f.as<rs2::video_frame>();
209  const int w = vf.get_width();
210  const int h = vf.get_height();
211  const int size = w * h;
212 
213  if (f.get_profile().format() == RS2_FORMAT_BGR8) {
214  memcpy(static_cast<void*>(img.ptr<cv::Vec3b>()), f.get_data(), size * 3);
215  } else if (f.get_profile().format() == RS2_FORMAT_RGB8) {
216  cv::Mat tmp(h, w, CV_8UC3, (void *)f.get_data(), cv::Mat::AUTO_STEP);
217  cv::cvtColor(tmp, img, cv::COLOR_RGB2BGR);
218  } else if (f.get_profile().format() == RS2_FORMAT_Y8) {
219  memcpy(img.ptr<uchar>(), f.get_data(), size);
220  }
221 }
222 #endif
223 }
224 
225 int main(int argc, char *argv[])
226 {
227 #ifdef VISP_HAVE_PCL
228  bool pcl_color = false;
229 #endif
230  bool show_info = false;
231 
232  for (int i = 1; i < argc; i++) {
233 #ifdef VISP_HAVE_PCL
234  if (std::string(argv[i]) == "--pcl_color") {
235  pcl_color = true;
236  } else
237 #endif
238  if (std::string(argv[i]) == "--show_info") {
239  show_info = true;
240  }
241  }
242 
243  if (show_info) {
244  vpRealSense2 rs;
245  rs.open();
246  std::cout << "RealSense:\n" << rs << std::endl;
247  return EXIT_SUCCESS;
248  }
249 
250  vpRealSense2 rs;
251  rs2::config config;
252  config.enable_stream(RS2_STREAM_COLOR, 1280, 720, RS2_FORMAT_RGBA8, 30);
253  config.enable_stream(RS2_STREAM_DEPTH, 1280, 720, RS2_FORMAT_Z16, 30);
254  config.enable_stream(RS2_STREAM_INFRARED, 1, 1280, 720, RS2_FORMAT_Y8, 30);
255  config.enable_stream(RS2_STREAM_INFRARED, 2, 1280, 720, RS2_FORMAT_Y8, 30);
256  rs.open(config);
257 
258  rs2::pipeline_profile &profile = rs.getPipelineProfile();
259  auto color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
260  vpImage<vpRGBa> color((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
261 
262  auto depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
263  vpImage<vpRGBa> depth_color((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
264  vpImage<uint16_t> depth_raw((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
265 
266  auto infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
267  vpImage<unsigned char> infrared1((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
268  vpImage<unsigned char> infrared2((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
269 
270 #ifdef VISP_HAVE_X11
271  vpDisplayX d1, d2, d3, d4;
272 #else
273  vpDisplayGDI d1, d2, d3, d4;
274 #endif
275  d1.init(color, 0, 0, "Color");
276  d2.init(depth_color, color.getWidth(), 0, "Depth");
277  d3.init(infrared1, 0, color.getHeight() + 100, "Infrared left");
278  d4.init(infrared2, color.getWidth(), color.getHeight() + 100, "Infrared right");
279 
280  std::vector<vpColVector> pointcloud_colvector;
281 #ifdef VISP_HAVE_PCL
282  std::mutex mutex;
283  ViewerWorker viewer_colvector(false, mutex);
284  std::thread viewer_colvector_thread(&ViewerWorker::run, &viewer_colvector);
285 #endif
286 
287  rs2::pipeline &pipe = rs.getPipeline();
288 
289  std::cout << "Color intrinsics:\n"
291  << std::endl;
292  std::cout << "Color intrinsics:\n"
293  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
294 
295  std::cout << "Depth intrinsics:\n"
297  << std::endl;
298  std::cout << "Depth intrinsics:\n"
299  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
300 
301  std::cout << "Infrared intrinsics:\n"
303  << std::endl;
304  std::cout << "Infrared intrinsics:\n"
306  << std::endl;
307 
308  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
309  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
310 
311  std::vector<double> time_vector;
312  double t_begin = vpTime::measureTimeMs();
313  while (vpTime::measureTimeMs() - t_begin < 10000) {
314  double t = vpTime::measureTimeMs();
315 
316  auto data = pipe.wait_for_frames();
317  auto color_frame = data.get_color_frame();
318  getNativeFrame(color_frame, (unsigned char *)color.bitmap);
319 
320  auto depth_frame = data.get_depth_frame();
321  getNativeFrame(depth_frame, (unsigned char *)depth_raw.bitmap);
322 
323 #if (RS2_API_VERSION >= ((2 * 10000) + (10 * 100) + 0))
324  // rs2::frameset::get_infrared_frame() introduced in librealsense 2.10.0
325  auto infrared1_frame = data.get_infrared_frame(1);
326  getNativeFrame(infrared1_frame, (unsigned char *)infrared1.bitmap);
327 
328  auto infrared2_frame = data.get_infrared_frame(2);
329  getNativeFrame(infrared2_frame, (unsigned char *)infrared2.bitmap);
330 #endif
331 
332 #ifdef VISP_HAVE_PCL
333  getPointcloud(depth_frame, pointcloud_colvector);
334 
335  {
336  std::lock_guard<std::mutex> lock(mutex);
337 
338  pointcloud->width = depth_profile.width();
339  pointcloud->height = depth_profile.height();
340  pointcloud->points.resize(pointcloud_colvector.size());
341  for (size_t i = 0; i < pointcloud_colvector.size(); i++) {
342  pointcloud->points[(size_t)i].x = pointcloud_colvector[i][0];
343  pointcloud->points[(size_t)i].y = pointcloud_colvector[i][1];
344  pointcloud->points[(size_t)i].z = pointcloud_colvector[i][2];
345  }
346 
347  update_pointcloud = true;
348  }
349 #endif
350 
351  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
352 
353  vpDisplay::display(color);
354  vpDisplay::display(depth_color);
355  vpDisplay::display(infrared1);
356  vpDisplay::display(infrared2);
357 
358  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
359 
360  vpDisplay::flush(color);
361  vpDisplay::flush(depth_color);
362  vpDisplay::flush(infrared1);
363  vpDisplay::flush(infrared2);
364 
365  time_vector.push_back(vpTime::measureTimeMs() - t);
366  if (vpDisplay::getClick(color, false))
367  break;
368  }
369 
370  rs.close();
371  d1.close(color);
372  d2.close(depth_color);
373  d3.close(infrared1);
374  d4.close(infrared2);
375 
376 #ifdef VISP_HAVE_PCL
377  {
378  std::lock_guard<std::mutex> lock(mutex);
379  cancelled = true;
380  }
381 
382  viewer_colvector_thread.join();
383 #endif
384  std::cout << "Acquisition1 - Mean time: " << vpMath::getMean(time_vector)
385  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
386 
387  config.disable_all_streams();
388  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 60);
389  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
390  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 60);
391  rs.open(config);
392 
393  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
394  color.init((unsigned int)color_profile.height(), (unsigned int)color_profile.width());
395 
396  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
397  depth_color.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
398  depth_raw.init((unsigned int)depth_profile.height(), (unsigned int)depth_profile.width());
399 
400  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
401  infrared1.init((unsigned int)infrared_profile.height(), (unsigned int)infrared_profile.width());
402 
403  d1.init(color, 0, 0, "Color");
404  d2.init(depth_color, color.getWidth(), 0, "Depth");
405  d3.init(infrared1, 0, color.getHeight() + 100, "Infrared");
406 
407 #ifdef VISP_HAVE_PCL
408  cancelled = false;
409  ViewerWorker viewer(pcl_color, mutex);
410  std::thread viewer_thread(&ViewerWorker::run, &viewer);
411 #endif
412 
413  std::cout << "\n" << std::endl;
414  std::cout << "Color intrinsics:\n"
416  << std::endl;
417  std::cout << "Color intrinsics:\n"
418  << rs.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
419 
420  std::cout << "Depth intrinsics:\n"
422  << std::endl;
423  std::cout << "Depth intrinsics:\n"
424  << rs.getCameraParameters(RS2_STREAM_DEPTH, vpCameraParameters::perspectiveProjWithDistortion) << std::endl;
425 
426  std::cout << "Infrared intrinsics:\n"
428  << std::endl;
429  std::cout << "Infrared intrinsics:\n"
431  << std::endl;
432 
433  std::cout << "depth_M_color:\n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
434  std::cout << "color_M_infrared:\n" << rs.getTransformation(RS2_STREAM_INFRARED, RS2_STREAM_COLOR) << std::endl;
435 
436  time_vector.clear();
437  t_begin = vpTime::measureTimeMs();
438  while (vpTime::measureTimeMs() - t_begin < 10000) {
439  double t = vpTime::measureTimeMs();
440 
441 #ifdef VISP_HAVE_PCL
442  {
443  std::lock_guard<std::mutex> lock(mutex);
444 
445  if (pcl_color) {
446  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud_color,
447  (unsigned char *)infrared1.bitmap);
448  } else {
449  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL, pointcloud,
450  (unsigned char *)infrared1.bitmap);
451  }
452 
453  update_pointcloud = true;
454  }
455 #else
456  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth_raw.bitmap, NULL,
457  (unsigned char *)infrared1.bitmap);
458 #endif
459 
460  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
461 
462  vpDisplay::display(color);
463  vpDisplay::display(depth_color);
464  vpDisplay::display(infrared1);
465 
466  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
467 
468  vpDisplay::flush(color);
469  vpDisplay::flush(depth_color);
470  vpDisplay::flush(infrared1);
471 
472  time_vector.push_back(vpTime::measureTimeMs() - t);
473  if (vpDisplay::getClick(color, false))
474  break;
475  }
476 
477 #ifdef VISP_HAVE_PCL
478  {
479  std::lock_guard<std::mutex> lock(mutex);
480  cancelled = true;
481  }
482 
483  viewer_thread.join();
484 #endif
485 
486  d1.close(color);
487  d2.close(depth_color);
488  d3.close(infrared1);
489  std::cout << "Acquisition2 - Mean time: " << vpMath::getMean(time_vector)
490  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
491 
492 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
493  rs.close();
494  config.disable_all_streams();
495  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_BGR8, 60);
496  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 60);
497  config.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 60);
498  config.enable_stream(RS2_STREAM_INFRARED, 2, 640, 480, RS2_FORMAT_Y8, 60);
499  rs.open(config);
500 
501  color_profile = profile.get_stream(RS2_STREAM_COLOR).as<rs2::video_stream_profile>();
502  cv::Mat mat_color(color_profile.height(), color_profile.width(), CV_8UC3);
503 
504  depth_profile = profile.get_stream(RS2_STREAM_DEPTH).as<rs2::video_stream_profile>();
505  cv::Mat mat_depth(depth_profile.height(), depth_profile.width(), CV_8UC3);
506  rs2::colorizer color_map;
507 
508  infrared_profile = profile.get_stream(RS2_STREAM_INFRARED).as<rs2::video_stream_profile>();
509  cv::Mat mat_infrared1(infrared_profile.height(), infrared_profile.width(), CV_8U);
510  cv::Mat mat_infrared2(infrared_profile.height(), infrared_profile.width(), CV_8U);
511 
512  time_vector.clear();
513  t_begin = vpTime::measureTimeMs();
514  while (vpTime::measureTimeMs() - t_begin < 10000) {
515  double t = vpTime::measureTimeMs();
516 
517  auto data = pipe.wait_for_frames();
518  frame_to_mat(data.get_color_frame(), mat_color);
519 #if (RS2_API_VERSION >= ((2 * 10000) + (16 * 100) + 0))
520  frame_to_mat(data.get_depth_frame().apply_filter(color_map), mat_depth);
521 #else
522  frame_to_mat(color_map(data.get_depth_frame()), mat_depth);
523 #endif
524 
525  cv::imshow("OpenCV color", mat_color);
526  cv::imshow("OpenCV depth", mat_depth);
527 
528 #if (RS2_API_VERSION >= ((2 * 10000) + (10 * 100) + 0))
529  // rs2::frameset::get_infrared_frame() introduced in librealsense 2.10.0
530  frame_to_mat(data.get_infrared_frame(1), mat_infrared1);
531  frame_to_mat(data.get_infrared_frame(2), mat_infrared2);
532 
533  cv::imshow("OpenCV infrared left", mat_infrared1);
534  cv::imshow("OpenCV infrared right", mat_infrared2);
535 #endif
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  return EXIT_SUCCESS;
547 }
548 
549 #else
550 int main()
551 {
552 #if !defined(VISP_HAVE_REALSENSE2)
553  std::cout << "Install librealsense2 to make this test work." << std::endl;
554 #endif
555 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
556  std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON) "
557  "to make this test work"
558  << std::endl;
559 #endif
560 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
561  std::cout << "X11 or GDI are needed." << std::endl;
562 #endif
563  return 0;
564 }
565 #endif
rs2::pipeline_profile & getPipelineProfile()
Get a reference to rs2::pipeline_profile.
Definition: vpRealSense2.h:325
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void close(vpImage< unsigned char > &I)
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:222
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:129
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
void open(const rs2::config &cfg=rs2::config())
static void flush(const vpImage< unsigned char > &I)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:88
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
Definition: vpTime.cpp:345
static const vpColor red
Definition: vpColor.h:180
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:202
static void display(const vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &grey)
rs2::pipeline & getPipeline()
Get a reference to rs2::pipeline.
Definition: vpRealSense2.h:322
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)