Visual Servoing Platform  version 3.6.1 under development (2024-05-10)
readRealSenseData.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 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 https://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 *****************************************************************************/
32 
39 #include <iostream>
40 
41 #include <visp3/core/vpConfig.h>
42 
43 #if defined(VISP_HAVE_THREADS) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI))
44 #include <condition_variable>
45 #include <fstream>
46 #include <mutex>
47 #include <queue>
48 #include <thread>
49 
50 #include <visp3/core/vpImageConvert.h>
51 #include <visp3/core/vpIoException.h>
52 #include <visp3/core/vpIoTools.h>
53 #include <visp3/gui/vpDisplayGDI.h>
54 #include <visp3/gui/vpDisplayX.h>
55 #include <visp3/gui/vpDisplayPCL.h>
56 #include <visp3/io/vpImageIo.h>
57 #include <visp3/io/vpParseArgv.h>
58 #include <visp3/io/vpVideoWriter.h>
59 
60 #if defined(VISP_HAVE_PCL)
61 #include <pcl/pcl_config.h>
62 #if defined(VISP_HAVE_PCL_COMMON)
63 #include <pcl/point_types.h>
64 #include <pcl/point_cloud.h>
65 #endif
66 #if defined(VISP_HAVE_PCL_IO)
67 #include <pcl/io/pcd_io.h>
68 #endif
69 #endif
70 
71 #define GETOPTARGS "ci:bodh"
72 
73 namespace
74 {
75 
76 void usage(const char *name, const char *badparam)
77 {
78  std::cout << "\nNAME " << std::endl
79  << " " << vpIoTools::getName(name)
80  << " - Read data acquired with a Realsense device." << std::endl
81  << std::endl
82  << "SYNOPSIS " << std::endl
83  << " " << name
84  << " [-i <directory>]"
85  << " [-c]"
86  << " [-b]"
87  << " [-o]"
88  << " [-d]"
89  << " [--help,-h]"
90  << std::endl;
91  std::cout << "\nOPTIONS " << std::endl
92  << " -i <directory>" << std::endl
93  << " Input folder that contains the data to read." << std::endl
94  << std::endl
95  << " -c" << std::endl
96  << " Flag to display data in step by step mode triggered by a user click." << std::endl
97  << std::endl
98  << " -b" << std::endl
99  << " Point cloud stream is saved in binary format." << std::endl
100  << std::endl
101  << " -o" << std::endl
102  << " Save color images in png format in a new folder." << std::endl
103  << std::endl
104  << " -d" << std::endl
105  << " Display depth in color." << std::endl
106  << std::endl
107  << " --help, -h" << std::endl
108  << " Display this helper message." << std::endl
109  << std::endl;
110 
111  if (badparam) {
112  std::cout << "\nERROR: Bad parameter " << badparam << std::endl;
113  }
114 }
115 
116 bool getOptions(int argc, const char *argv[], std::string &input_directory, bool &click, bool &pointcloud_binary_format,
117  bool &save_video, bool &color_depth)
118 {
119  const char *optarg;
120  const char **argv1 = (const char **)argv;
121  int c;
122  while ((c = vpParseArgv::parse(argc, argv1, GETOPTARGS, &optarg)) > 1) {
123 
124  switch (c) {
125  case 'i':
126  input_directory = optarg;
127  break;
128  case 'c':
129  click = true;
130  break;
131  case 'b':
132  pointcloud_binary_format = true;
133  break;
134  case 'o':
135  save_video = true;
136  break;
137  case 'd':
138  color_depth = true;
139  break;
140 
141  case 'h':
142  usage(argv[0], nullptr);
143  return false;
144  break;
145 
146  default:
147  usage(argv[0], optarg);
148  return false;
149  break;
150  }
151  }
152 
153  if ((c == 1) || (c == -1)) {
154  // standalone param or error
155  usage(argv[0], nullptr);
156  std::cerr << "ERROR: " << std::endl;
157  std::cerr << " Bad argument " << optarg << std::endl << std::endl;
158  return false;
159  }
160 
161  return true;
162 }
163 
164 bool readData(int cpt, const std::string &input_directory, vpImage<vpRGBa> &I_color, vpImage<uint16_t> &I_depth_raw,
165  bool pointcloud_binary_format
166 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
167  , pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud
168 #endif
169 )
170 {
171  char buffer[FILENAME_MAX];
172  std::stringstream ss;
173  ss << input_directory << "/color_image_%04d.jpg";
174  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
175  std::string filename_color = buffer;
176 
177  ss.str("");
178  ss << input_directory << "/depth_image_%04d.bin";
179  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
180  std::string filename_depth = buffer;
181 
182  ss.str("");
183  ss << input_directory << "/point_cloud_%04d" << (pointcloud_binary_format ? ".bin" : ".pcd");
184  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
185  std::string filename_pointcloud = buffer;
186 
187  if (!vpIoTools::checkFilename(filename_color) && !vpIoTools::checkFilename(filename_depth) &&
188  !vpIoTools::checkFilename(filename_pointcloud)) {
189  std::cerr << "End of sequence." << std::endl;
190  return false;
191  }
192 
193  // Read color
194  if (vpIoTools::checkFilename(filename_color)) {
195  vpImageIo::read(I_color, filename_color);
196  }
197 
198  // Read raw depth
199  std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
200  if (file_depth.is_open()) {
201  unsigned int height = 0, width = 0;
202  vpIoTools::readBinaryValueLE(file_depth, height);
203  vpIoTools::readBinaryValueLE(file_depth, width);
204  I_depth_raw.resize(height, width);
205 
206  uint16_t depth_value = 0;
207  for (unsigned int i = 0; i < height; i++) {
208  for (unsigned int j = 0; j < width; j++) {
209  vpIoTools::readBinaryValueLE(file_depth, depth_value);
210  I_depth_raw[i][j] = depth_value;
211  }
212  }
213  }
214 
215  // Read pointcloud
216 #if defined(VISP_HAVE_PCL)
217  if (pointcloud_binary_format) {
218  std::ifstream file_pointcloud(filename_pointcloud.c_str(), std::ios::in | std::ios::binary);
219  if (!file_pointcloud.is_open()) {
220  std::cerr << "Cannot read pointcloud file: " << filename_pointcloud << std::endl;
221  }
222 
223  uint32_t height = 0, width = 0;
224  char is_dense = 1;
225  vpIoTools::readBinaryValueLE(file_pointcloud, height);
226  vpIoTools::readBinaryValueLE(file_pointcloud, width);
227  file_pointcloud.read((char *)(&is_dense), sizeof(is_dense));
228 
229  point_cloud->width = width;
230  point_cloud->height = height;
231  point_cloud->is_dense = (is_dense != 0);
232  point_cloud->resize((size_t)width * height);
233 
234  float x = 0.0f, y = 0.0f, z = 0.0f;
235  for (uint32_t i = 0; i < height; i++) {
236  for (uint32_t j = 0; j < width; j++) {
237  vpIoTools::readBinaryValueLE(file_pointcloud, x);
238  vpIoTools::readBinaryValueLE(file_pointcloud, y);
239  vpIoTools::readBinaryValueLE(file_pointcloud, z);
240 
241  point_cloud->points[(size_t)(i * width + j)].x = x;
242  point_cloud->points[(size_t)(i * width + j)].y = y;
243  point_cloud->points[(size_t)(i * width + j)].z = z;
244  }
245  }
246  }
247  else {
248 #if defined(VISP_HAVE_PCL_IO)
249  if (pcl::io::loadPCDFile<pcl::PointXYZ>(filename_pointcloud, *point_cloud) == -1) {
250  std::cerr << "Cannot read PCD: " << filename_pointcloud << std::endl;
251  }
252 #else
253  throw(vpIoException(vpIoException::ioError, "Cannot read pcd file without PCL io module"));
254 #endif
255  }
256 #endif
257 
258  return true;
259 }
260 } // Namespace
261 
262 int main(int argc, const char *argv[])
263 {
264  std::string input_directory = "";
265  bool click = false;
266  bool pointcloud_binary_format = false;
267  bool save_video = false;
268  bool color_depth = false;
269 
270  // Read the command line options
271  if (!getOptions(argc, argv, input_directory, click, pointcloud_binary_format, save_video, color_depth)) {
272  return EXIT_FAILURE;
273  }
274 
275  vpImage<vpRGBa> I_color(480, 640), I_depth_color(480, 640);
276  vpImage<uint16_t> I_depth_raw(480, 640);
277  vpImage<unsigned char> I_depth(480, 640);
278 
279 #ifdef VISP_HAVE_X11
280  vpDisplayX d1, d2;
281 #else
282  vpDisplayGDI d1, d2;
283 #endif
284  bool init_display = false;
285 
286 #if defined(VISP_HAVE_PCL)
287  std::mutex mutex;
288  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
289 #if defined(VISP_HAVE_PCL_VISUALIZATION)
290  vpDisplayPCL pcl_viewer;
291 #endif
292 #endif
293 
294  vpVideoWriter writer;
295  vpImage<vpRGBa> O;
296  if (save_video) {
297  std::string output_directory = vpTime::getDateTime("%Y-%m-%d_%H.%M.%S");
298  vpIoTools::makeDirectory(output_directory);
299  writer.setFileName(output_directory + "/%04d.png");
300  }
301 
302  int cpt_frame = 0;
303  bool quit = false;
304  while (!quit) {
305  double t = vpTime::measureTimeMs();
306 
307 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
308  {
309  std::lock_guard<std::mutex> lock(mutex);
310  quit = !readData(cpt_frame, input_directory, I_color, I_depth_raw, pointcloud_binary_format, pointcloud);
311  }
312 #else
313  quit = !readData(cpt_frame, input_directory, I_color, I_depth_raw, pointcloud_binary_format);
314 #endif
315 
316  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
317  if (color_depth)
318  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth_color);
319 
320  if (!init_display) {
321  init_display = true;
322  d1.init(I_color, 0, 0, "Color image");
323  if (color_depth) {
324  d2.init(I_depth_color, I_color.getWidth() + 10, 0, "Depth image");
325  }
326  else {
327  d2.init(I_depth, I_color.getWidth() + 10, 0, "Depth image");
328  }
329 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
330  pcl_viewer.setPosition(I_color.getWidth() + 10, I_color.getHeight() + 70);
331  pcl_viewer.setWindowName("3D point cloud");
332  pcl_viewer.startThread(std::ref(mutex), pointcloud);
333 #endif
334  }
335 
336  vpDisplay::display(I_color);
337  if (color_depth)
338  vpDisplay::display(I_depth_color);
339  else
340  vpDisplay::display(I_depth);
341 
342  std::stringstream ss;
343  ss << "Frame: " << cpt_frame;
344  vpDisplay::displayText(I_color, 20, 20, ss.str(), vpColor::red);
345  if (color_depth)
346  vpDisplay::displayText(I_depth_color, 20, 20, ss.str(), vpColor::red);
347  else
348  vpDisplay::displayText(I_depth, 20, 20, ss.str(), vpColor::red);
349 
350  vpDisplay::flush(I_color);
351  if (color_depth)
352  vpDisplay::flush(I_depth_color);
353  else
354  vpDisplay::flush(I_depth);
355 
356  if (save_video) {
357  if (O.getSize() == 0) {
358  O.resize(I_color.getHeight(), I_color.getWidth() + I_depth_color.getWidth());
359  writer.open(O);
360  }
361 
362  O.insert(I_color, vpImagePoint());
363  if (!color_depth)
364  vpImageConvert::convert(I_depth, I_depth_color);
365  O.insert(I_depth_color, vpImagePoint(0, I_color.getWidth()));
366  writer.saveFrame(O);
367  }
368 
370  if (vpDisplay::getClick(I_color, button, click)) {
371  switch (button) {
373  if (!quit)
374  quit = !click;
375  break;
376 
378  click = !click;
379  break;
380 
381  default:
382  break;
383  }
384  }
385 
386  vpTime::wait(t, 30);
387  cpt_frame++;
388  }
389 
390  return EXIT_SUCCESS;
391 }
392 #else
393 int main()
394 {
395  std::cerr << "Enable C++11 or higher (cmake -DUSE_CXX_STANDARD=11) and install X11 or GDI!" << std::endl;
396  return EXIT_SUCCESS;
397 }
398 #endif
static const vpColor red
Definition: vpColor.h:211
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:128
void init(vpImage< unsigned char > &I, int win_x=-1, int win_y=-1, const std::string &win_title="") vp_override
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
@ ioError
I/O error.
Definition: vpException.h:79
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:143
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
unsigned int getWidth() const
Definition: vpImage.h:245
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:783
void insert(const vpImage< Type > &src, const vpImagePoint &topLeft)
Definition: vpImage.h:1533
unsigned int getSize() const
Definition: vpImage.h:224
unsigned int getHeight() const
Definition: vpImage.h:184
Error that can be emitted by the vpIoTools class and its derivatives.
Definition: vpIoException.h:54
static bool checkFilename(const std::string &filename)
Definition: vpIoTools.cpp:1213
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
Definition: vpIoTools.cpp:2520
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:981
static std::string getName(const std::string &pathname)
Definition: vpIoTools.cpp:1981
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:69
Class that enables to write easily a video file or a sequence of images.
void saveFrame(vpImage< vpRGBa > &I)
void setFileName(const std::string &filename)
void open(vpImage< vpRGBa > &I)
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
VISP_EXPORT double measureTimeMs()