Visual Servoing Platform  version 3.6.1 under development (2024-05-14)
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:e:jbzodh"
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  << " [-e <filename pattern (e.g. %04d)>]"
86  << " [-c]"
87  << " [-j]"
88  << " [-b]"
89  << " [-z]"
90  << " [-o]"
91  << " [-d]"
92  << " [--help,-h]"
93  << std::endl;
94  std::cout << "\nOPTIONS " << std::endl
95  << " -i <directory>" << std::endl
96  << " Input folder that contains the data to read." << std::endl
97  << std::endl
98  << " -e <pattern>" << std::endl
99  << " Filename pattern, e.g. %04d." << std::endl
100  << std::endl
101  << " -c" << std::endl
102  << " Flag to display data in step by step mode triggered by a user click." << std::endl
103  << std::endl
104  << " -j" << std::endl
105  << " Image data are saved in JPEG format, otherwise in PNG." << std::endl
106  << std::endl
107  << " -b" << std::endl
108  << " Depth and Pointcloud streams are saved in binary format." << std::endl
109  << std::endl
110  << " -z" << std::endl
111  << " Pointcloud stream is saved in NPZ format." << std::endl
112  << std::endl
113  << " -o" << std::endl
114  << " Save color images in PNG format (lossless) in a new folder." << std::endl
115  << std::endl
116  << " -d" << std::endl
117  << " Display depth in color." << std::endl
118  << std::endl
119  << " --help, -h" << std::endl
120  << " Display this helper message." << std::endl
121  << std::endl;
122 
123  if (badparam) {
124  std::cout << "\nERROR: Bad parameter " << badparam << std::endl;
125  }
126 }
127 
128 bool getOptions(int argc, const char *argv[], std::string &input_directory, std::string &pattern, bool &click,
129  bool &force_binary_format, bool &read_jpeg, bool &read_npz, bool &save_video, bool &color_depth)
130 {
131  const char *optarg;
132  const char **argv1 = (const char **)argv;
133  int c;
134  while ((c = vpParseArgv::parse(argc, argv1, GETOPTARGS, &optarg)) > 1) {
135 
136  switch (c) {
137  case 'i':
138  input_directory = optarg;
139  break;
140  case 'e':
141  pattern = optarg;
142  break;
143  case 'c':
144  click = true;
145  break;
146  case 'j':
147  read_jpeg = true;
148  break;
149  case 'b':
150  force_binary_format = true;
151  break;
152  case 'z':
153  read_npz = true;
154  break;
155  case 'o':
156  save_video = true;
157  break;
158  case 'd':
159  color_depth = true;
160  break;
161 
162  case 'h':
163  usage(argv[0], nullptr);
164  return false;
165  break;
166 
167  default:
168  usage(argv[0], optarg);
169  return false;
170  break;
171  }
172  }
173 
174  if ((c == 1) || (c == -1)) {
175  // standalone param or error
176  usage(argv[0], nullptr);
177  std::cerr << "ERROR: " << std::endl;
178  std::cerr << " Bad argument " << optarg << std::endl << std::endl;
179  return false;
180  }
181 
182  return true;
183 }
184 
185 bool readData(int cpt, const std::string &input_directory, const std::string &pattern, vpImage<vpRGBa> &I_color,
186  vpImage<uint16_t> &I_depth_raw, bool force_binary_format, bool read_jpeg, bool read_npz
187 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
188  , pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud
189 #endif
190 )
191 {
192  std::string image_filename_ext = read_jpeg ? ".jpg" : ".png";
193  std::string depth_filename_ext = force_binary_format ? ".bin" : ".npz";
194  char buffer[FILENAME_MAX];
195  std::stringstream ss;
196  ss << input_directory << "/color_image_" << pattern << image_filename_ext;
197  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
198  std::string filename_color = buffer;
199 
200  ss.str("");
201  ss << input_directory << "/depth_image_" << pattern << depth_filename_ext;
202  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
203  std::string filename_depth = buffer;
204 
205  ss.str("");
206  ss << input_directory << "/point_cloud_" << pattern << (force_binary_format ? ".bin" :
207  (read_npz ? ".npz" : ".pcd"));
208  snprintf(buffer, FILENAME_MAX, ss.str().c_str(), cpt);
209  std::string filename_pointcloud = buffer;
210 
211  if (!vpIoTools::checkFilename(filename_color) && !vpIoTools::checkFilename(filename_depth) &&
212  !vpIoTools::checkFilename(filename_pointcloud)) {
213  std::cerr << "End of sequence." << std::endl;
214  return false;
215  }
216 
217  // Read color
218  if (vpIoTools::checkFilename(filename_color)) {
219  vpImageIo::read(I_color, filename_color);
220  }
221 
222  // Read raw depth
223  if (vpIoTools::checkFilename(filename_depth)) {
224  if (force_binary_format) {
225  std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
226  if (file_depth.is_open()) {
227  unsigned int height = 0, width = 0;
228  vpIoTools::readBinaryValueLE(file_depth, height);
229  vpIoTools::readBinaryValueLE(file_depth, width);
230  I_depth_raw.resize(height, width);
231 
232  uint16_t depth_value = 0;
233  for (unsigned int i = 0; i < height; i++) {
234  for (unsigned int j = 0; j < width; j++) {
235  vpIoTools::readBinaryValueLE(file_depth, depth_value);
236  I_depth_raw[i][j] = depth_value;
237  }
238  }
239  }
240  }
241  else {
242  visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_depth);
243 
244  // Load depth data
245  visp::cnpy::NpyArray arr_depth_data = npz_data["data"];
246  if (arr_depth_data.data_holder == nullptr) {
247  throw vpIoException(vpIoException::ioError, "Loaded NPZ data is null.");
248  }
249 
250  uint16_t *depth_data_ptr = arr_depth_data.data<uint16_t>();
251  assert(arr_depth_data.shape.size() == 3); // H x W x C
252  assert(arr_depth_data.shape[2] == 1); // Single channel
253 
254  unsigned int height = arr_depth_data.shape[0], width = arr_depth_data.shape[1];
255  const bool copyData = true;
256  I_depth_raw = vpImage<uint16_t>(depth_data_ptr, height, width, copyData);
257  }
258  }
259 
260  // Read pointcloud
261  if (vpIoTools::checkFilename(filename_pointcloud)) {
262 #if defined(VISP_HAVE_PCL)
263  // TODO: not tested
264  if (force_binary_format) {
265  std::ifstream file_pointcloud(filename_pointcloud.c_str(), std::ios::in | std::ios::binary);
266  if (!file_pointcloud.is_open()) {
267  std::cerr << "Cannot read pointcloud file: " << filename_pointcloud << std::endl;
268  }
269 
270  uint32_t height = 0, width = 0;
271  const char is_dense = 1;
272  vpIoTools::readBinaryValueLE(file_pointcloud, height);
273  vpIoTools::readBinaryValueLE(file_pointcloud, width);
274  file_pointcloud.read((char *)(&is_dense), sizeof(is_dense));
275 
276  point_cloud->width = width;
277  point_cloud->height = height;
278  point_cloud->is_dense = (is_dense != 0);
279  point_cloud->resize((size_t)width * height);
280 
281  float x = 0.0f, y = 0.0f, z = 0.0f;
282  for (uint32_t i = 0; i < height; i++) {
283  for (uint32_t j = 0; j < width; j++) {
284  vpIoTools::readBinaryValueLE(file_pointcloud, x);
285  vpIoTools::readBinaryValueLE(file_pointcloud, y);
286  vpIoTools::readBinaryValueLE(file_pointcloud, z);
287 
288  point_cloud->points[(size_t)(i * width + j)].x = x;
289  point_cloud->points[(size_t)(i * width + j)].y = y;
290  point_cloud->points[(size_t)(i * width + j)].z = z;
291  }
292  }
293  }
294  else if (read_npz) {
295  visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_pointcloud);
296 
297  // Load pointcloud data
298  visp::cnpy::NpyArray arr_pcl_data = npz_data["data"];
299  if (arr_pcl_data.data_holder == nullptr) {
300  throw vpIoException(vpIoException::ioError, "Loaded NPZ data is null.");
301  }
302 
303  float *pcl_data_ptr = arr_pcl_data.data<float>();
304  assert(arr_pcl_data.shape.size() == 3); // H x W x C
305  assert(arr_pcl_data.shape[2] == 3); // 3-channels: X, Y, Z
306 
307  uint32_t height = arr_pcl_data.shape[0], width = arr_pcl_data.shape[1];
308  const char is_dense = 1;
309 
310  point_cloud->width = width;
311  point_cloud->height = height;
312  point_cloud->is_dense = (is_dense != 0);
313  point_cloud->resize((size_t)width * height);
314 
315  for (uint32_t i = 0; i < height; i++) {
316  for (uint32_t j = 0; j < width; j++) {
317  point_cloud->points[(size_t)(i * width + j)].x = pcl_data_ptr[(size_t)(i * width + j)*3 + 0];
318  point_cloud->points[(size_t)(i * width + j)].y = pcl_data_ptr[(size_t)(i * width + j)*3 + 1];
319  point_cloud->points[(size_t)(i * width + j)].z = pcl_data_ptr[(size_t)(i * width + j)*3 + 2];
320  }
321  }
322  }
323  else {
324 #if defined(VISP_HAVE_PCL_IO)
325  if (pcl::io::loadPCDFile<pcl::PointXYZ>(filename_pointcloud, *point_cloud) == -1) {
326  std::cerr << "Cannot read PCD: " << filename_pointcloud << std::endl;
327  }
328 #else
329  throw(vpIoException(vpIoException::ioError, "Cannot read pcd file without PCL io module"));
330 #endif
331  }
332 #endif
333  }
334 
335  return true;
336 }
337 } // Namespace
338 
339 int main(int argc, const char *argv[])
340 {
341  std::string input_directory = "";
342  std::string pattern = "%04d";
343  bool click = false;
344  bool force_binary_format = false;
345  bool save_video = false;
346  bool color_depth = false;
347  bool read_jpeg = false;
348  bool read_npz = false;
349 
350  // Read the command line options
351  if (!getOptions(argc, argv, input_directory, pattern, click, force_binary_format, read_jpeg, read_npz,
352  save_video, color_depth)) {
353  return EXIT_FAILURE;
354  }
355 
356  vpImage<vpRGBa> I_color(480, 640), I_depth_color(480, 640);
357  vpImage<uint16_t> I_depth_raw(480, 640);
358  vpImage<unsigned char> I_depth(480, 640);
359 
360 #ifdef VISP_HAVE_X11
361  vpDisplayX d1, d2;
362 #else
363  vpDisplayGDI d1, d2;
364 #endif
365  bool init_display = false;
366 
367 #if defined(VISP_HAVE_PCL)
368  std::mutex mutex;
369  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
370 #if defined(VISP_HAVE_PCL_VISUALIZATION)
371  vpDisplayPCL pcl_viewer;
372 #endif
373 #endif
374 
375  vpVideoWriter writer;
376  vpImage<vpRGBa> O;
377  if (save_video) {
378  std::string output_directory = vpTime::getDateTime("%Y-%m-%d_%H.%M.%S");
379  vpIoTools::makeDirectory(output_directory);
380  writer.setFileName(output_directory + "/" + pattern + ".png");
381  }
382 
383  int cpt_frame = 0;
384  bool quit = false;
385  while (!quit) {
386  double t = vpTime::measureTimeMs();
387 
388 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
389  {
390  std::lock_guard<std::mutex> lock(mutex);
391  quit = !readData(cpt_frame, input_directory, pattern, I_color, I_depth_raw, force_binary_format, read_jpeg,
392  read_npz, pointcloud);
393  }
394 #else
395  quit = !readData(cpt_frame, input_directory, pattern, I_color, I_depth_raw, force_binary_format, read_jpeg,
396  read_npz);
397 #endif
398 
399  if (color_depth)
400  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth_color);
401  else
402  vpImageConvert::createDepthHistogram(I_depth_raw, I_depth);
403 
404  if (!init_display) {
405  init_display = true;
406  d1.init(I_color, 0, 0, "Color image");
407  if (color_depth) {
408  d2.init(I_depth_color, I_color.getWidth() + 10, 0, "Depth image");
409  }
410  else {
411  d2.init(I_depth, I_color.getWidth() + 10, 0, "Depth image");
412  }
413 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
414  pcl_viewer.setPosition(I_color.getWidth() + 10, I_color.getHeight() + 70);
415  pcl_viewer.setWindowName("3D point cloud");
416  pcl_viewer.startThread(std::ref(mutex), pointcloud);
417 #endif
418  }
419 
420  vpDisplay::display(I_color);
421  if (color_depth)
422  vpDisplay::display(I_depth_color);
423  else
424  vpDisplay::display(I_depth);
425 
426  std::stringstream ss;
427  ss << "Frame: " << cpt_frame;
428  vpDisplay::displayText(I_color, 20, 20, ss.str(), vpColor::red);
429  if (color_depth)
430  vpDisplay::displayText(I_depth_color, 20, 20, ss.str(), vpColor::red);
431  else
432  vpDisplay::displayText(I_depth, 20, 20, ss.str(), vpColor::red);
433 
434  vpDisplay::flush(I_color);
435  if (color_depth)
436  vpDisplay::flush(I_depth_color);
437  else
438  vpDisplay::flush(I_depth);
439 
440  if (save_video) {
441  if (O.getSize() == 0) {
442  O.resize(I_color.getHeight(), I_color.getWidth() + I_depth_color.getWidth());
443  writer.open(O);
444  }
445 
446  O.insert(I_color, vpImagePoint());
447  if (!color_depth)
448  vpImageConvert::convert(I_depth, I_depth_color);
449  O.insert(I_depth_color, vpImagePoint(0, I_color.getWidth()));
450  writer.saveFrame(O);
451  }
452 
454  if (vpDisplay::getClick(I_color, button, click)) {
455  switch (button) {
457  if (!quit)
458  quit = !click;
459  break;
460 
462  click = !click;
463  break;
464 
465  default:
466  break;
467  }
468  }
469 
470  vpTime::wait(t, 30);
471  cpt_frame++;
472  }
473 
474  return EXIT_SUCCESS;
475 }
476 #else
477 int main()
478 {
479  std::cerr << "Enable C++11 or higher (cmake -DUSE_CXX_STANDARD=11) and install X11 or GDI!" << std::endl;
480  return EXIT_SUCCESS;
481 }
482 #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:1215
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
Definition: vpIoTools.cpp:2522
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:983
static std::string getName(const std::string &pathname)
Definition: vpIoTools.cpp:1983
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 npz_t npz_load(std::string fname)
Definition: vpIoTools.cpp:342
std::map< std::string, NpyArray > npz_t
Definition: vpIoTools.h:126
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()
std::shared_ptr< std::vector< char > > data_holder
Definition: vpIoTools.h:119
std::vector< size_t > shape
Definition: vpIoTools.h:120