Visual Servoing Platform  version 3.1.0
grabRealSense2.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 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) && defined(VISP_HAVE_CPP11_COMPATIBILITY) && \
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 
57 namespace
58 {
59 // Global variables
60 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
61 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
62 bool cancelled = false, update_pointcloud = false;
63 
64 class ViewerWorker
65 {
66 public:
67  explicit ViewerWorker(const bool color_mode, std::mutex &mutex) : m_colorMode(color_mode), m_mutex(mutex) {}
68 
69  void run()
70  {
71  std::string date = vpTime::getDateTime();
72  pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("3D Viewer " + date));
73  pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointcloud_color);
74  pcl::PointCloud<pcl::PointXYZ>::Ptr local_pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
75  pcl::PointCloud<pcl::PointXYZRGB>::Ptr local_pointcloud_color(new pcl::PointCloud<pcl::PointXYZRGB>());
76 
77  viewer->setBackgroundColor(0, 0, 0);
78  viewer->initCameraParameters();
79  viewer->setPosition(640 + 80, 480 + 80);
80  viewer->setCameraPosition(0, 0, -0.25, 0, -1, 0);
81  viewer->setSize(640, 480);
82 
83  bool init = true;
84  bool local_update = false, local_cancelled = false;
85  while (!local_cancelled) {
86  {
87  std::unique_lock<std::mutex> lock(m_mutex, std::try_to_lock);
88 
89  if (lock.owns_lock()) {
90  local_update = update_pointcloud;
91  update_pointcloud = false;
92  local_cancelled = cancelled;
93 
94  if (local_update) {
95  if (m_colorMode) {
96  local_pointcloud_color = pointcloud_color->makeShared();
97  } else {
98  local_pointcloud = pointcloud->makeShared();
99  }
100  }
101  }
102  }
103 
104  if (local_update && !local_cancelled) {
105  local_update = false;
106 
107  if (init) {
108  if (m_colorMode) {
109  viewer->addPointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
110  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1,
111  "RGB sample cloud");
112  } else {
113  viewer->addPointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
114  viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
115  }
116  init = false;
117  } else {
118  if (m_colorMode) {
119  viewer->updatePointCloud<pcl::PointXYZRGB>(local_pointcloud_color, rgb, "RGB sample cloud");
120  } else {
121  viewer->updatePointCloud<pcl::PointXYZ>(local_pointcloud, "sample cloud");
122  }
123  }
124  }
125 
126  viewer->spinOnce(5);
127  }
128 
129  std::cout << "End of point cloud display thread" << std::endl;
130  }
131 
132 private:
133  bool m_colorMode;
134  std::mutex &m_mutex;
135 };
136 }
137 #endif
138 
139 int main()
140 {
141  try {
142  vpRealSense2 rs;
143  rs2::config config;
144  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
145  config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
146  config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
147  rs.open(config);
148 
150  << std::endl;
152  << std::endl;
153  std::cout << "Extrinsics cMd: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_DEPTH) << std::endl;
154  std::cout << "Extrinsics dMc: \n" << rs.getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_COLOR) << std::endl;
155  std::cout << "Extrinsics cMi: \n" << rs.getTransformation(RS2_STREAM_COLOR, RS2_STREAM_INFRARED) << std::endl;
156  std::cout << "Extrinsics dMi: \n" << rs.getTransformation(RS2_STREAM_DEPTH, RS2_STREAM_INFRARED) << std::endl;
157 
158  vpImage<vpRGBa> color((unsigned int)rs.getIntrinsics(RS2_STREAM_COLOR).height,
159  (unsigned int)rs.getIntrinsics(RS2_STREAM_COLOR).width);
160  vpImage<unsigned char> infrared((unsigned int)rs.getIntrinsics(RS2_STREAM_INFRARED).height,
161  (unsigned int)rs.getIntrinsics(RS2_STREAM_INFRARED).width);
162  vpImage<vpRGBa> depth_display((unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).height,
163  (unsigned int)rs.getIntrinsics(RS2_STREAM_DEPTH).width);
164  vpImage<uint16_t> depth(depth_display.getHeight(), depth_display.getWidth());
165 
166 #ifdef VISP_HAVE_PCL
167  std::mutex mutex;
168  ViewerWorker viewer(true, mutex);
169  std::thread viewer_thread(&ViewerWorker::run, &viewer);
170 #endif
171 
172 #if defined(VISP_HAVE_X11)
173  vpDisplayX dc(color, 10, 10, "Color image");
174  vpDisplayX di(infrared, (int)color.getWidth() + 80, 10, "Infrared image");
175  vpDisplayX dd(depth_display, 10, (int)color.getHeight() + 80, "Depth image");
176 #elif defined(VISP_HAVE_GDI)
177  vpDisplayGDI dc(color, 10, 10, "Color image");
178  vpDisplayGDI di(infrared, color.getWidth() + 80, 10, "Infrared image");
179  vpDisplayGDI dd(depth_display, 10, color.getHeight() + 80, "Depth image");
180 #endif
181 
182  while (true) {
183  double t = vpTime::measureTimeMs();
184 
185 #ifdef VISP_HAVE_PCL
186  {
187  std::lock_guard<std::mutex> lock(mutex);
188  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, pointcloud_color,
189  (unsigned char *)infrared.bitmap);
190  update_pointcloud = true;
191  }
192 #else
193  rs.acquire((unsigned char *)color.bitmap, (unsigned char *)depth.bitmap, NULL, (unsigned char *)infrared.bitmap);
194 #endif
195 
196  vpImageConvert::createDepthHistogram(depth, depth_display);
197 
198  vpDisplay::display(color);
199  vpDisplay::display(infrared);
200  vpDisplay::display(depth_display);
201 
202  vpDisplay::displayText(color, 15, 15, "Click to quit", vpColor::red);
203  if (vpDisplay::getClick(color, false) || vpDisplay::getClick(infrared, false) ||
204  vpDisplay::getClick(depth_display, false)) {
205  break;
206  }
207  vpDisplay::flush(color);
208  vpDisplay::flush(infrared);
209  vpDisplay::flush(depth_display);
210 
211  std::cout << "Loop time: " << vpTime::measureTimeMs() - t << std::endl;
212  }
213 
214  std::cout << "RealSense sensor characteristics: \n" << rs << std::endl;
215 
216 #ifdef VISP_HAVE_PCL
217  {
218  std::lock_guard<std::mutex> lock(mutex);
219  cancelled = true;
220  }
221 
222  viewer_thread.join();
223 #endif
224 
225  } catch (const vpException &e) {
226  std::cerr << "RealSense error " << e.what() << std::endl;
227  } catch (const std::exception &e) {
228  std::cerr << e.what() << std::endl;
229  }
230 
231  return 0;
232 }
233 #else
234 int main()
235 {
236 #if !defined(VISP_HAVE_REALSENSE2)
237  std::cout << "Install librealsense2." << std::endl;
238 #endif
239 #if !defined(VISP_HAVE_CPP11_COMPATIBILITY)
240  std::cout << "Build ViSP with C++11 compiler flag (cmake -DUSE_CPP11=ON)." << std::endl;
241 #endif
242  return 0;
243 }
244 #endif
rs2_intrinsics getIntrinsics(const rs2_stream &stream) const
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
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
error that can be emited by ViSP classes.
Definition: vpException.h:71
void open(const rs2::config &cfg=rs2::config())
static void flush(const vpImage< unsigned char > &I)
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 void display(const vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &grey)
const char * what() const
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
vpHomogeneousMatrix getTransformation(const rs2_stream &from, const rs2_stream &to) const
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)