Visual Servoing Platform  version 3.4.0
testRealSense2_D435_pcl.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 (PCL demo).
33  *
34  *****************************************************************************/
40 #include <iostream>
41 
42 #include <visp3/core/vpConfig.h>
43 
44 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
45  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_PCL)
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 #include <pcl/visualization/cloud_viewer.h>
54 #include <pcl/visualization/pcl_visualizer.h>
55 #include <thread>
56 #include <mutex>
57 
58 namespace
59 {
60 // Global variables
61 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
62 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
63 bool cancelled = false, update_pointcloud = false;
64 
65 class ViewerWorker
66 {
67 public:
68  explicit ViewerWorker(bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
69 
70  void run()
71  {
72  std::string date = vpTime::getDateTime();
73  pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
74  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
75  pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
76  pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
77 
78  viewer->setBackgroundColor(0, 0, 0);
79  viewer->initCameraParameters();
80  viewer->setPosition(640 + 80, 480 + 80);
81  viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
82  viewer->setSize(640, 480);
83 
84  bool init = true;
85  bool local_update = false, local_cancelled = false;
86  while (!local_cancelled) {
87  {
88  std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
89 
90  if (lock.owns_lock()) {
91  local_update = update_pointcloud;
92  update_pointcloud = false;
93  local_cancelled = cancelled;
94 
95  if (local_update) {
96  if (m_colorMode) {
97  local_pointcloud_color = pointcloud_color->makeShared();
98  } else {
99  local_pointcloud = pointcloud->makeShared();
100  }
101  }
102  }
103  }
104 
105  if (local_update && !local_cancelled) {
106  local_update = false;
107 
108  if (init) {
109  if (m_colorMode) {
110  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
111  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
112  "RGB sample cloud");
113  } else {
114  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
115  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
116  }
117  init = false;
118  } else {
119  if (m_colorMode) {
120  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
121  } else {
122  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
123  }
124  }
125  }
126 
127  viewer->spinOnce(5);
128  }
129 
130  std::cout << "End of point cloud display thread" << std::endl;
131  }
132 
133 private:
134  bool m_colorMode;
135  std::mutex &m_mutex;
136 };
137 }
138 
139 int main(int argc, char *argv[])
140 {
141  bool pcl_color = false;
142  bool show_infrared2 = false;
143  for (int i = 1; i < argc; i++) {
144  if (std::string(argv[i]) == "--pcl_color") {
145  pcl_color = true;
146  } else if (std::string(argv[i]) == "--show_infrared2") {
147  show_infrared2 = true;
148  }
149  }
150 
151  const int width = 640, height = 480, fps = 30;
152  vpRealSense2 rs;
153  rs2::config config;
154  config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
155  config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
156  config.enable_stream(RS2_STREAM_INFRARED, 1, width, height, RS2_FORMAT_Y8, fps);
157  config.enable_stream(RS2_STREAM_INFRARED, 2, width, height, RS2_FORMAT_Y8, fps);
158  rs.open(config);
159 
160  vpImage<vpRGBa> color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
161  vpImage<vpRGBa> depth_color(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
162  vpImage<uint16_t> depth_raw(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
163  vpImage<unsigned char> infrared1(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
164  vpImage<unsigned char> infrared2(static_cast<unsigned int>(height), static_cast<unsigned int>(width));
165 
166 #ifdef VISP_HAVE_X11
167  vpDisplayX d1, d2, d3, d4;
168 #else
169  vpDisplayGDI d1, d2, d3, d4;
170 #endif
171  d1.init(color, 0, 0, "Color");
172  d2.init(depth_color, color.getWidth(), 0, "Depth");
173  d3.init(infrared1, 0, color.getHeight() + 100, "Infrared left");
174  if (show_infrared2) {
175  d4.init(infrared2, color.getWidth(), color.getHeight() + 100, "Infrared right");
176  }
177 
178  std::mutex mutex;
179  ViewerWorker viewer_pointcloud(pcl_color, mutex);
180  std::thread viewer_thread(&ViewerWorker::run, &viewer_pointcloud);
181 
182  std::vector<double> time_vector;
183  vpChrono chrono;
184  while (true) {
185  chrono.start();
186  {
187  std::lock_guard<std::mutex> lock(mutex);
188 
189  if (pcl_color) {
190  rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap),
191  reinterpret_cast<unsigned char *>(depth_raw.bitmap),
192  NULL, pointcloud_color,
193  reinterpret_cast<unsigned char *>(infrared1.bitmap),
194  show_infrared2 ? reinterpret_cast<unsigned char *>(infrared2.bitmap) : NULL,
195  NULL);
196  } else {
197  rs.acquire(reinterpret_cast<unsigned char *>(color.bitmap),
198  reinterpret_cast<unsigned char *>(depth_raw.bitmap),
199  NULL, pointcloud,
200  reinterpret_cast<unsigned char *>(infrared1.bitmap),
201  show_infrared2 ? reinterpret_cast<unsigned char *>(infrared2.bitmap) : NULL,
202  NULL);
203  }
204 
205  update_pointcloud = true;
206  }
207 
208  vpImageConvert::createDepthHistogram(depth_raw, depth_color);
209 
210  vpDisplay::display(color);
211  vpDisplay::display(depth_color);
212  vpDisplay::display(infrared1);
213  vpDisplay::display(infrared2);
214 
215  vpDisplay::displayText(color, 20, 20, "Click to quit.", vpColor::red);
216  vpDisplay::displayText(depth_color, 20, 20, "Click to quit.", vpColor::red);
217  vpDisplay::displayText(infrared1, 20, 20, "Click to quit.", vpColor::red);
218  vpDisplay::displayText(infrared2, 20, 20, "Click to quit.", vpColor::red);
219 
220  vpDisplay::flush(color);
221  vpDisplay::flush(depth_color);
222  vpDisplay::flush(infrared1);
223  vpDisplay::flush(infrared2);
224 
225  chrono.stop();
226  time_vector.push_back(chrono.getDurationMs());
227  if (vpDisplay::getClick(color, false) ||
228  vpDisplay::getClick(depth_color, false) ||
229  vpDisplay::getClick(infrared1, false) ||
230  vpDisplay::getClick(infrared2, false)) {
231  break;
232  }
233  }
234 
235  {
236  std::lock_guard<std::mutex> lock(mutex);
237  cancelled = true;
238  }
239  viewer_thread.join();
240 
241  std::cout << "Acquisition - Mean time: " << vpMath::getMean(time_vector)
242  << " ms ; Median time: " << vpMath::getMedian(time_vector) << " ms" << std::endl;
243 
244  return EXIT_SUCCESS;
245 }
246 
247 #else
248 int main()
249 {
250 #if !defined(VISP_HAVE_REALSENSE2)
251  std::cout << "Install librealsense2 to make this test work." << std::endl;
252 #endif
253 #if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
254  std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11) "
255  "to make this test work"
256  << std::endl;
257 #endif
258 #if !defined(VISP_HAVE_X11) && !defined(VISP_HAVE_GDI)
259  std::cout << "X11 or GDI are needed." << std::endl;
260 #endif
261 #if !defined(VISP_HAVE_PCL)
262  std::cout << "Install PCL to make this test work." << std::endl;
263 #endif
264  return 0;
265 }
266 #endif
double getDurationMs()
Definition: vpTime.cpp:392
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static double getMedian(const std::vector< double > &v)
Definition: vpMath.cpp:220
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
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:150
static void flush(const vpImage< unsigned char > &I)
bool open(const rs2::config &cfg=rs2::config())
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
Definition: vpTime.cpp:358
static const vpColor red
Definition: vpColor.h:217
void start(bool reset=true)
Definition: vpTime.cpp:409
static double getMean(const std::vector< double > &v)
Definition: vpMath.cpp:200
void stop()
Definition: vpTime.cpp:424
static void display(const vpImage< unsigned char > &I)
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="")
void acquire(vpImage< unsigned char > &grey, double *ts=NULL)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)