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