Visual Servoing Platform  version 3.4.0
grabRealSense2.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  * Acquisition with RealSense RGB-D sensor and librealsense2.
33  *
34  *****************************************************************************/
35 
42 #include <iostream>
43 
44 #include <visp3/core/vpImageConvert.h>
45 #include <visp3/gui/vpDisplayGDI.h>
46 #include <visp3/gui/vpDisplayX.h>
47 #include <visp3/sensor/vpRealSense2.h>
48 
49 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
50  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
51 
52 #ifdef VISP_HAVE_PCL
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 #endif
139 
140 int main()
141 {
142  try {
143  vpRealSense2 rs;
144 
145  std::string product_line = rs.getProductLine();
146  std::cout << "Product line: " << product_line << std::endl;
147 
148  if (product_line == "T200") {
149  std::cout << "This example doesn't support T200 product line family !" << std::endl;
150  return EXIT_SUCCESS;
151  }
152  rs2::config config;
153  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
154  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
155  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
156  rs.open(config);
157 
159  << std::endl;
161  << std::endl;
162  std::cout << "Extrinsics cMd: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
163  std::cout << "Extrinsics dMc: \n" << rs.getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_COLOR) << std::endl;
164  std::cout << "Extrinsics cMi: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_INFRARED) << std::endl;
165  std::cout << "Extrinsics dMi: \n" << rs.getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_INFRARED) << std::endl;
166 
167  vpImage<vpRGBa> color((unsigned int)rs.getIntrinsics(RS2_STREAM_COLOR).height,
168  (unsigned int)rs.getIntrinsics(RS2_STREAM_COLOR).width);
169  vpImage<unsigned char> infrared((unsigned int)rs.getIntrinsics(RS2_STREAM_INFRARED).height,
170  (unsigned int)rs.getIntrinsics(RS2_STREAM_INFRARED).width);
171  vpImage<vpRGBa> depth_display((unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).height,
172  (unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).width);
173  vpImage<uint16_t> depth(depth_display.getHeight(), depth_display.getWidth());
174 
175 #ifdef VISP_HAVE_PCL
176  std::mutex mutex;
177  ViewerWorker viewer(true, mutex);
178  std::thread viewer_thread(&ViewerWorker::run, &viewer);
179 #endif
180 
181 #if defined(VISP_HAVE_X11)
182  vpDisplayX dc(color, 10, 10, "Color image");
183  vpDisplayX di(infrared, (int)color.getWidth() + 80, 10, "Infrared image");
184  vpDisplayX dd(depth_display, 10, (int)color.getHeight() + 80, "Depth image");
185 #elif defined(VISP_HAVE_GDI)
186  vpDisplayGDI dc(color, 10, 10, "Color image");
187  vpDisplayGDI di(infrared, color.getWidth() + 80, 10, "Infrared image");
188  vpDisplayGDI dd(depth_display, 10, color.getHeight() + 80, "Depth image");
189 #endif
190 
191  while (true) {
192  double t = vpTime::measureTimeMs();
193 
194 #ifdef VISP_HAVE_PCL
195  {
196  std::lock_guard<std::mutex> lock(mutex);
197  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
198  (unsigned char *)infrared.bitmap);
199  update_pointcloud = true;
200  }
201 #else
202  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)infrared.bitmap);
203 #endif
204 
205  vpImageConvert::createDepthHistogram(depth, depth_display);
206 
207  vpDisplay::display(color);
208  vpDisplay::display(infrared);
209  vpDisplay::display(depth_display);
210 
211  vpDisplay::displayText(color, 15, 15, "Click to quit", vpColor::red);
212  if (vpDisplay::getClick(color, false) || vpDisplay::getClick(infrared, false) ||
213  vpDisplay::getClick(depth_display, false)) {
214  break;
215  }
216  vpDisplay::flush(color);
217  vpDisplay::flush(infrared);
218  vpDisplay::flush(depth_display);
219 
220  std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl;
221  }
222 
223  std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
224 
225 #ifdef VISP_HAVE_PCL
226  {
227  std::lock_guard<std::mutex> lock(mutex);
228  cancelled = true;
229  }
230 
231  viewer_thread.join();
232 #endif
233 
234  } catch (const vpException &e) {
235  std::cerr << "RealSense error " << e.what() << std::endl;
236  } catch (const std::exception &e) {
237  std::cerr << e.what() << std::endl;
238  }
239 
240  return EXIT_SUCCESS;
241 }
242 #else
243 int main()
244 {
245 #if !defined(VISP_HAVE_REALSENSE2)
246  std::cout << "You do not realsense2 SDK functionality enabled..." << std::endl;
247  std::cout << "Tip:" << std::endl;
248  std::cout << "- Install librealsense2, configure again ViSP using cmake and build again this example" << std::endl;
249  return EXIT_SUCCESS;
250 #endif
251 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
252  std::cout << "You do not build ViSP with c++11 or higher compiler flag" << std::endl;
253  std::cout << "Tip:" << std::endl;
254  std::cout << "- Configure ViSP again using cmake -DUSE_CXX_STANDARD=11, and build again this example" << std::endl;
255 #endif
256  return EXIT_SUCCESS;
257 }
258 #endif
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
std::string getProductLine()
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
error that can be emited by ViSP classes.
Definition: vpException.h:71
static void flush(const vpImage< unsigned char > &I)
bool open(const rs2::config &cfg=rs2::config())
VISP_EXPORT double measureTimeMs()
Definition: vpTime.cpp:126
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
const char * what() const
static void display(const vpImage< unsigned char > &I)
rs2_intrinsics getIntrinsics(const rs2_stream &stream, int index=-1) const
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to, int from_index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=NULL)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)