Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
visp-read-rs-dataset.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 */
30
36
37#include <iostream>
38
39#include <visp3/core/vpConfig.h>
40
41#if defined(VISP_HAVE_THREADS) && defined(VISP_HAVE_DISPLAY)
42#include <condition_variable>
43#include <fstream>
44#include <mutex>
45#include <queue>
46#include <thread>
47
48#include <visp3/core/vpImageConvert.h>
49#include <visp3/core/vpIoException.h>
50#include <visp3/core/vpIoTools.h>
51#include <visp3/gui/vpDisplayFactory.h>
52#include <visp3/gui/vpDisplayPCL.h>
53#include <visp3/io/vpImageIo.h>
54#include <visp3/io/vpVideoReader.h>
55#include <visp3/io/vpVideoWriter.h>
56
57#if defined(VISP_HAVE_PCL)
58#include <pcl/pcl_config.h>
59#if defined(VISP_HAVE_PCL_COMMON)
60#include <pcl/point_types.h>
61#include <pcl/point_cloud.h>
62#endif
63#if defined(VISP_HAVE_PCL_IO)
64#include <pcl/io/pcd_io.h>
65#endif
66#endif
67
68#ifdef ENABLE_VISP_NAMESPACE
69using namespace VISP_NAMESPACE_NAME;
70#endif
71
72namespace
73{
74void usage(const char *argv[], int error)
75{
76 std::cout << "\nNAME " << std::endl
77 << " " << vpIoTools::getName(argv[0])
78 << " - Replay data (color, depth, infrared, point cloud) acquired" << std::endl
79 << " with a Realsense device using visp-save-rs-dataset app." << std::endl;
80
81 std::cout << "\nDESCRIPTION " << std::endl
82 << " This app allows to replay a dataset (color, depth, infrared, point cloud)" << std::endl
83 << " acquired with a Realsense device using visp-save-rs-dataset app." << std::endl;
84
85 std::cout << "\nSYNOPSIS " << std::endl
86 << " " << vpIoTools::getName(argv[0])
87 << " [--input-folder,-i <input folder>]"
88 << " [--pattern,-e <filename numbering pattern (e.g. %06d)>]"
89 << " [--step-by-step,-s]"
90 << " [--save-video,-o]"
91 << " [--display-colored-depth,-colored-depth]"
92 << " [--loop,-l]"
93 << " [--fps,-f <framerate>]"
94 << " [--help,-h]"
95 << std::endl;
96
97 std::cout << "\nOPTIONS " << std::endl
98 << " --input-folder,-i <input folder>" << std::endl
99 << " Input folder that contains the data to read." << std::endl
100 << std::endl
101 << " --pattern,-e <filename numbering pattern (e.g. %06d)>" << std::endl
102 << " Filename numbering pattern used when saving data." << std::endl
103 << std::endl
104 << " --step-by-step,-s" << std::endl
105 << " Flag to display data in step by step mode triggered by a user click." << std::endl
106 << std::endl
107 << " --save-video,-o" << std::endl
108 << " Creates and saves a new image with the color image on the left and" << std::endl
109 << " the depth image on the right. Images are saved in a new folder" << std::endl
110 << " that corresponds to the date of the day with the following format" << std::endl
111 << " YYYY-MM-DD_HH.MM.SS, for example 2025-11-10_17.06.57."
112 << std::endl
113 << " --display-colored-depth,-colored-depth" << std::endl
114 << " Display depth using a cumulative histogram." << std::endl
115 << " Warning: this operation is time consuming" << std::endl
116 << std::endl
117 << " --loop,-l" << std::endl
118 << " When this option is enabled, once the sequence has reached the end," << std::endl
119 << " playback will restart from the first frame." << std::endl
120 << std::endl
121 << " --fps,-f <framerate>" << std::endl
122 << " Framerate in Hz used to playback the dataset." << std::endl
123 << " Default: 30 fps" << std::endl
124 << std::endl
125 << " --help,-h" << std::endl
126 << " Display this helper message." << std::endl
127 << std::endl;
128
129 std::cout << "EXAMPLE " << std::endl
130 << "- Read dataset in data folder" << std::endl
131 << " " << argv[0] << " --input-folder data --display-colored-depth" << std::endl
132 << std::endl;
133
134 if (error) {
135 std::cout << "Error" << std::endl
136 << " "
137 << "Unsupported parameter " << argv[error] << std::endl;
138 }
139}
140
141bool getOptions(int argc, const char *argv[], std::string &input_folder, std::string &numbering_pattern,
142 bool &step_by_step, bool &save_video, bool &display_colored_depth, bool &loop, double &fps)
143{
144 for (int i = 1; i < argc; i++) {
145 if (((std::string(argv[i]) == "--input-folder") || (std::string(argv[i]) == "-i")) && (i + 1 < argc)) {
146 input_folder = std::string(argv[++i]);
147 }
148 else if (((std::string(argv[i]) == "--pattern") || (std::string(argv[i]) == "-e")) && (i + 1 < argc)) {
149 numbering_pattern = std::string(argv[++i]);
150 }
151 else if ((std::string(argv[i]) == "--step-by-step") || (std::string(argv[i]) == "-s")) {
152 step_by_step = true;
153 }
154 else if ((std::string(argv[i]) == "--save-video") || (std::string(argv[i]) == "-o")) {
155 save_video = true;
156 }
157 else if ((std::string(argv[i]) == "--display-colored-depth") || (std::string(argv[i]) == "-colored-depth")) {
158 display_colored_depth = true;
159 }
160 else if ((std::string(argv[i]) == "--loop") || (std::string(argv[i]) == "-l")) {
161 loop = true;
162 }
163 else if (((std::string(argv[i]) == "--fps") || (std::string(argv[i]) == "-f")) && (i + 1 < argc)) {
164 fps = std::atof(argv[++i]);
165 }
166 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
167 usage(argv, 0);
168 return false;
169 }
170 else {
171 usage(argv, i);
172 return false;
173 }
174 }
175
176 return true;
177}
178
179void checkData(unsigned int cpt_frame, const std::string &input_folder, const std::string &input_pattern,
180 bool &color_found, std::string &color_ext,
181 bool &depth_found, std::string &depth_ext,
182 bool &infra_found, std::string &infra_ext,
183 bool &pcl_found, std::string &pcl_ext,
184 unsigned int &frame_first, unsigned int &frame_last)
185{
186 // Check if color present
187 {
188 std::vector<std::string> ext;
189 ext.push_back(".jpg");
190 ext.push_back(".png");
191 for (size_t i = 0; i < ext.size(); ++i) {
192 std::string f = vpIoTools::formatString(input_folder + "/color_image_" + input_pattern + ext[i], cpt_frame);
194 color_ext = ext[i];
195 color_found = true;
196 break;
197 }
198 }
199 }
200
201 // Check if depth present
202 {
203 std::vector<std::string> ext;
204 ext.push_back(".bin");
205#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
206 ext.push_back(".npz");
207#endif
208 for (size_t i = 0; i < ext.size(); ++i) {
209 std::string f = vpIoTools::formatString(input_folder + "/depth_image_" + input_pattern + ext[i], cpt_frame);
211 depth_ext = ext[i];
212 depth_found = true;
213 break;
214 }
215 }
216 }
217
218 // Check if infrared present
219 {
220 std::vector<std::string> ext;
221 ext.push_back(".jpg");
222 ext.push_back(".png");
223 for (size_t i = 0; i < ext.size(); ++i) {
224 std::string f = vpIoTools::formatString(input_folder + "/infrared_image_" + input_pattern + ext[i], cpt_frame);
226 infra_ext = ext[i];
227 infra_found = true;
228 break;
229 }
230 }
231 }
232 // Check if point cloud present
233 {
234 std::vector<std::string> ext;
235 ext.push_back(".bin");
236#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
237 ext.push_back(".npz");
238#endif
239#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_IO) && defined(VISP_HAVE_PCL_COMMON)
240 ext.push_back(".pcd");
241#endif
242 for (size_t i = 0; i < ext.size(); ++i) {
243 std::string f = vpIoTools::formatString(input_folder + "/point_cloud_" + input_pattern + ext[i], cpt_frame);
245 pcl_ext = ext[i];
246 pcl_found = true;
247 break;
248 }
249 }
250 }
251
252 // Get first and last frame index
253 {
255 if (color_found) {
256 g.setFileName(input_folder + "/color_image_" + input_pattern + color_ext);
257 }
258 else if (infra_found) {
259 g.setFileName(input_folder + "/infrared_image_" + input_pattern + infra_ext);
260 }
261 else {
262 std::cout << "WARNING: Unable to find first and last frame index images" << std::endl;
263 return;
264 }
266 g.open(I);
267 frame_first = g.getFirstFrameIndex();
268 frame_last = g.getLastFrameIndex();
269 g.close();
270 }
271}
272
278bool readData(int cpt, const std::string &input_folder, const std::string &input_pattern,
279 bool color_found, std::string color_ext,
280 bool depth_found, std::string depth_ext,
281 bool infra_found, std::string infra_ext,
282 vpImage<vpRGBa> &I_color, vpImage<uint16_t> &I_depth_raw, vpImage<unsigned char> &I_infra,
283 std::string &filename_color, std::string &filename_depth, std::string &filename_infra
284#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
285 , bool pcl_found, std::string pcl_ext, std::string &filename_pcl
286 , pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud
287#endif
288)
289{
290 filename_color = vpIoTools::formatString(input_folder + "/color_image_" + input_pattern + color_ext, cpt);
291 filename_depth = vpIoTools::formatString(input_folder + "/depth_image_" + input_pattern + depth_ext, cpt);
292 filename_infra = vpIoTools::formatString(input_folder + "/infrared_image_" + input_pattern + infra_ext, cpt);
293#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
294 filename_pcl = vpIoTools::formatString(input_folder + "/point_cloud_" + input_pattern + pcl_ext, cpt);
295#endif
296
297 if (!vpIoTools::checkFilename(filename_color) && !vpIoTools::checkFilename(filename_depth) &&
298 !vpIoTools::checkFilename(filename_infra)
299#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
300 && !vpIoTools::checkFilename(filename_pcl)
301#endif
302 ) {
303 std::cerr << "End of sequence." << std::endl;
304 return false;
305 }
306
307 // Read color
308 if (color_found) {
309 if (vpIoTools::checkFilename(filename_color)) {
310 vpImageIo::read(I_color, filename_color);
311 }
312 }
313
314 // Read raw depth
315 if (depth_found) {
316 if (vpIoTools::checkFilename(filename_depth)) {
317 if (depth_ext == ".bin") { // Use binary format
318 std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
319 if (file_depth.is_open()) {
320 unsigned int height = 0, width = 0;
321 vpIoTools::readBinaryValueLE(file_depth, height);
322 vpIoTools::readBinaryValueLE(file_depth, width);
323 I_depth_raw.resize(height, width);
324
325 uint16_t depth_value = 0;
326 for (unsigned int i = 0; i < height; i++) {
327 for (unsigned int j = 0; j < width; j++) {
328 vpIoTools::readBinaryValueLE(file_depth, depth_value);
329 I_depth_raw[i][j] = depth_value;
330 }
331 }
332 }
333 }
334 else if (depth_ext == ".npz") {
335#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
336 visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_depth);
337
338 // Load depth data
339 visp::cnpy::NpyArray arr_depth_data = npz_data["data"];
340 if (arr_depth_data.data_holder == nullptr) {
341 throw vpIoException(vpIoException::ioError, "Loaded NPZ data is null.");
342 }
343
344 uint16_t *depth_data_ptr = arr_depth_data.data<uint16_t>();
345 assert(arr_depth_data.shape.size() == 3); // H x W x C
346 assert(arr_depth_data.shape[2] == 1); // Single channel
347
348 unsigned int height = static_cast<unsigned int>(arr_depth_data.shape[0]);
349 unsigned int width = static_cast<unsigned int>(arr_depth_data.shape[1]);
350 const bool copyData = true;
351 I_depth_raw = vpImage<uint16_t>(depth_data_ptr, height, width, copyData);
352
353#else
354 throw(vpIoException(vpIoException::ioError, "Cannot read depth image in npz format."));
355#endif
356 }
357 }
358 }
359
360 // Read infrared
361 if (infra_found) {
362 if (vpIoTools::checkFilename(filename_infra)) {
363 vpImageIo::read(I_infra, filename_infra);
364 }
365 }
366
367 // Read pointcloud
368#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
369 if (pcl_found) {
370 if (vpIoTools::checkFilename(filename_pcl)) {
371 if (pcl_ext == ".npz") {
372#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
373 visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_pcl);
374
375 // Load pointcloud data
376 visp::cnpy::NpyArray arr_pcl_data = npz_data["data"];
377 if (arr_pcl_data.data_holder == nullptr) {
378 throw vpIoException(vpIoException::ioError, "Loaded NPZ data is null.");
379 }
380
381 float *pcl_data_ptr = arr_pcl_data.data<float>();
382 assert(arr_pcl_data.shape.size() == 3); // H x W x C
383 assert(arr_pcl_data.shape[2] == 3); // 3-channels: X, Y, Z
384
385 uint32_t height = arr_pcl_data.shape[0], width = arr_pcl_data.shape[1];
386 const char is_dense = 1;
387
388 point_cloud->width = width;
389 point_cloud->height = height;
390 point_cloud->is_dense = (is_dense != 0);
391 point_cloud->resize(static_cast<size_t>(width * height));
392
393 for (uint32_t i = 0; i < height; i++) {
394 for (uint32_t j = 0; j < width; j++) {
395 point_cloud->points[static_cast<size_t>(i * width + j)].x = pcl_data_ptr[static_cast<size_t>(i * width + j)*3 + 0];
396 point_cloud->points[static_cast<size_t>(i * width + j)].y = pcl_data_ptr[static_cast<size_t>(i * width + j)*3 + 1];
397 point_cloud->points[static_cast<size_t>(i * width + j)].z = pcl_data_ptr[static_cast<size_t>(i * width + j)*3 + 2];
398 }
399 }
400#endif
401 }
402 else if (pcl_ext == ".pcd") {
403#if defined(VISP_HAVE_PCL_IO)
404 if (pcl::io::loadPCDFile<pcl::PointXYZ>(filename_pcl, *point_cloud) == -1) {
405 std::cerr << "Cannot read PCD: " << filename_pcl << std::endl;
406 }
407#else
408 throw(vpIoException(vpIoException::ioError, "Cannot read pcd file without PCL io module"));
409#endif
410 }
411 else if (pcl_ext == ".bin") {
412 std::ifstream file_pointcloud(filename_pcl.c_str(), std::ios::in | std::ios::binary);
413 if (!file_pointcloud.is_open()) {
414 std::cerr << "Cannot read pointcloud file: " << filename_pcl << std::endl;
415 }
416
417 uint32_t height = 0, width = 0;
418 const char is_dense = 1;
419 vpIoTools::readBinaryValueLE(file_pointcloud, height);
420 vpIoTools::readBinaryValueLE(file_pointcloud, width);
421 file_pointcloud.read((char *)(&is_dense), sizeof(is_dense));
422
423 point_cloud->width = width;
424 point_cloud->height = height;
425 point_cloud->is_dense = (is_dense != 0);
426 point_cloud->resize(static_cast<size_t>(width * height));
427
428 float x = 0.0f, y = 0.0f, z = 0.0f;
429 for (uint32_t i = 0; i < height; i++) {
430 for (uint32_t j = 0; j < width; j++) {
431 vpIoTools::readBinaryValueLE(file_pointcloud, x);
432 vpIoTools::readBinaryValueLE(file_pointcloud, y);
433 vpIoTools::readBinaryValueLE(file_pointcloud, z);
434
435 point_cloud->points[static_cast<size_t>(i * width + j)].x = x;
436 point_cloud->points[static_cast<size_t>(i * width + j)].y = y;
437 point_cloud->points[static_cast<size_t>(i * width + j)].z = z;
438 }
439 }
440 }
441 }
442 }
443#endif
444
445 return true;
446}
447} // Namespace
448
449int main(int argc, const char *argv[])
450{
451 std::string opt_input_folder = "";
452 std::string opt_input_pattern = "%04d";
453 bool opt_step_by_step = false;
454 bool opt_save_video = false;
455 bool opt_display_colored_depth = false;
456 bool opt_loop = false;
457 double opt_fps = 30.0; // Hz
458
459 // Read the command line options
460 if (!getOptions(argc, argv, opt_input_folder, opt_input_pattern, opt_step_by_step,
461 opt_save_video, opt_display_colored_depth, opt_loop, opt_fps)) {
462 return EXIT_FAILURE;
463 }
464
465 vpImage<vpRGBa> I_color, I_depth_color;
466 vpImage<uint16_t> I_depth_raw;
467 vpImage<unsigned char> I_depth_gray, I_infra;
468
469#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
470 std::shared_ptr<vpDisplay> d1 = vpDisplayFactory::createDisplay(); // color
471 std::shared_ptr<vpDisplay> d2 = vpDisplayFactory::createDisplay(); // depth
472 std::shared_ptr<vpDisplay> d3 = vpDisplayFactory::createDisplay(); // infrared
473#else
477#endif
478
479 bool init_display = false;
480
481#if defined(VISP_HAVE_PCL)
482 std::mutex mutex;
483 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(new pcl::PointCloud<pcl::PointXYZ>());
484#if defined(VISP_HAVE_PCL_VISUALIZATION)
485 vpDisplayPCL pcl_viewer;
486#endif
487#endif
488
489 vpVideoWriter writer;
491 std::string output_folder = vpTime::getDateTime("%Y-%m-%d_%H.%M.%S");
492 if (opt_save_video) {
493 vpIoTools::makeDirectory(output_folder);
494 writer.setFileName(output_folder + "/" + opt_input_pattern + ".png");
495 }
496
497 unsigned int cpt_frame = 0;
498 bool color_found = false;
499 bool depth_found = false;
500 bool infra_found = false;
501 bool pcl_found = false;
502 std::string color_ext, depth_ext, infra_ext, pcl_ext;
503 unsigned int frame_first = 0, frame_last = 0;
504
505 checkData(cpt_frame, opt_input_folder, opt_input_pattern,
506 color_found, color_ext,
507 depth_found, depth_ext,
508 infra_found, infra_ext,
509 pcl_found, pcl_ext,
510 frame_first, frame_last);
511
512 std::cout << "Dataset in " << opt_input_folder << " contains" << std::endl;
513 std::cout << " - Color images : " << (color_found ? "yes" : "no") << std::endl;
514 std::cout << " - Depth images : " << (depth_found ? "yes" : "no") << std::endl;
515 std::cout << " - Infrared images : " << (infra_found ? "yes" : "no") << std::endl;
516 std::cout << " - Point cloud : " << (pcl_found ? "yes" : "no") << std::endl;
517 std::cout << "Dataset" << std::endl;
518 std::cout << " - First frame index: " << frame_first << std::endl;
519 std::cout << " - Last frame index: " << frame_last << std::endl;
520
521
522 std::cout << "Options summary" << std::endl;
523 std::cout << " Data visualization " << std::endl;
524 std::cout << " Colored depth : " << (opt_display_colored_depth ? "yes" : "no") << std::endl;
525 std::cout << " Frame per seconds: " << opt_fps << std::endl;
526 std::cout << " Save dataset : " << (opt_save_video ? "yes" : "no") << std::endl;
527 if (opt_save_video) {
528 std::cout << " Output folder : " << output_folder << std::endl;
529 }
530
531 if (!color_found && !depth_found && !infra_found && !pcl_found) {
532 std::cout << "\nError: No data found in " << opt_input_folder << " folder" << std::endl;
533 return EXIT_FAILURE;
534 }
535 bool quit = false;
536 std::string filename_color, filename_depth, filename_infra, filename_pcl;
537
538 while (!quit) {
539 double t = vpTime::measureTimeMs();
540#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
541 {
542 std::lock_guard<std::mutex> lock(mutex);
543 quit = !readData(cpt_frame, opt_input_folder, opt_input_pattern,
544 color_found, color_ext,
545 depth_found, depth_ext,
546 infra_found, infra_ext,
547 I_color, I_depth_raw, I_infra,
548 filename_color, filename_depth, filename_infra,
549 pcl_found, pcl_ext, filename_pcl, pointcloud);
550 }
551#else
552 quit = !readData(cpt_frame, opt_input_folder, opt_input_pattern,
553 color_found, color_ext,
554 depth_found, depth_ext,
555 infra_found, infra_ext,
556 I_color, I_depth_raw, I_infra,
557 filename_color, filename_depth, filename_infra);
558#endif
559
560 if (opt_display_colored_depth) {
561 vpImageConvert::createDepthHistogram(I_depth_raw, I_depth_color);
562 }
563 else {
564 vpImageConvert::createDepthHistogram(I_depth_raw, I_depth_gray);
565 }
566
567 if (!init_display) {
568 init_display = true;
569 if (color_found) {
570 d1->init(I_color, 0, 0, "Color image");
571 }
572 if (depth_found) {
573 if (opt_display_colored_depth) {
574 d2->init(I_depth_color, I_color.getWidth() + 80, 0, "Depth image");
575 }
576 else {
577 d2->init(I_depth_gray, I_color.getWidth() + 80, 0, "Depth image");
578 }
579 }
580 if (infra_found) {
581 d3->init(I_infra, I_color.getWidth() + 80, I_color.getHeight() + 70, "Infrared image");
582 }
583#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
584 if (pcl_found) {
585 if (pointcloud->size() > 0) {
586 pcl_viewer.setPosition(0, I_color.getHeight() + 70);
587 pcl_viewer.setWindowName("3D point cloud");
588 pcl_viewer.startThread(std::ref(mutex), pointcloud);
589 }
590 }
591#endif
592 }
593
594 vpDisplay::display(I_color);
595 vpDisplay::setTitle(I_color, "Color image: " + vpIoTools::getName(filename_color));
596 if (opt_step_by_step) {
597 vpDisplay::displayText(I_color, 15, 15, "Left click to view next data", vpColor::red);
598 vpDisplay::displayText(I_color, 30, 15, "Right click to switch to continuous mode", vpColor::red);
599 }
600 else {
601 vpDisplay::displayText(I_color, 15, 15, "Left click to quit", vpColor::red);
602 vpDisplay::displayText(I_color, 30, 15, "Right click to switch to step-by-step mode", vpColor::red);
603 }
604 if (opt_display_colored_depth) {
605 vpDisplay::display(I_depth_color);
606 vpDisplay::setTitle(I_depth_color, "Colored depth image: " + vpIoTools::getName(filename_depth));
607 }
608 else {
609 vpDisplay::display(I_depth_gray);
610 vpDisplay::setTitle(I_depth_color, "Depth image: " + vpIoTools::getName(filename_depth));
611 }
612 vpDisplay::display(I_infra);
613 vpDisplay::setTitle(I_infra, "Infrared image: " + vpIoTools::getName(filename_infra));
614
615 vpDisplay::flush(I_color);
616 if (opt_display_colored_depth) {
617 vpDisplay::flush(I_depth_color);
618 }
619 else {
620 vpDisplay::flush(I_depth_gray);
621 }
622 vpDisplay::flush(I_infra);
623
624 if (opt_save_video) {
625 if (O.getSize() == 0) {
626 O.resize(I_color.getHeight(), I_color.getWidth() + I_depth_color.getWidth());
627 writer.open(O);
628 }
629
630 O.insert(I_color, vpImagePoint());
631 if (!opt_display_colored_depth) {
632 vpImageConvert::convert(I_depth_gray, I_depth_color);
633 }
634 O.insert(I_depth_color, vpImagePoint(0, I_color.getWidth()));
635 writer.saveFrame(O);
636 }
637
639 if (vpDisplay::getClick(I_color, button, opt_step_by_step)) {
640 switch (button) {
642 if (!quit)
643 quit = !opt_step_by_step;
644 break;
645
647 opt_step_by_step = !opt_step_by_step;
648 break;
649
650 default:
651 break;
652 }
653 }
654
655 vpTime::wait(t, 1000. / opt_fps);
656 cpt_frame++;
657 if (opt_loop) {
658 if (cpt_frame == frame_last) {
659 std::cout << "End of sequence reached" << std::endl;
660 cpt_frame = frame_first;
661 }
662 }
663 }
664
665#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
666 if (d1 != nullptr) {
667 delete d1;
668 }
669 if (d2 != nullptr) {
670 delete d2;
671 }
672 if (d3 != nullptr) {
673 delete d3;
674 }
675#endif
676
677 return EXIT_SUCCESS;
678}
679#else
680int main()
681{
682 std::cerr << "Enable C++11 or higher (cmake -DUSE_CXX_STANDARD=11) and install X11 or GDI!" << std::endl;
683 return EXIT_SUCCESS;
684}
685#endif
static const vpColor red
Definition vpColor.h:198
void setPosition(int posx, int posy)
void setWindowName(const std::string &window_name)
void startThread(const bool &colorThread=false)
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void setTitle(const vpImage< unsigned char > &I, const std::string &windowtitle)
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:67
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)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition of the vpImage class member functions.
Definition vpImage.h:131
unsigned int getWidth() const
Definition vpImage.h:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition vpImage.h:544
void insert(const vpImage< Type > &src, const vpImagePoint &topLeft)
Definition vpImage.h:639
unsigned int getSize() const
Definition vpImage.h:221
unsigned int getHeight() const
Definition vpImage.h:181
Error that can be emitted by the vpIoTools class and its derivatives.
static bool checkFilename(const std::string &filename)
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
static std::string formatString(const std::string &name, unsigned int val)
static void makeDirectory(const std::string &dirname)
static std::string getName(const std::string &pathname)
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
long getLastFrameIndex()
void open(vpImage< vpRGBa > &I) VP_OVERRIDE
void setFileName(const std::string &filename)
long getFirstFrameIndex()
void close() VP_OVERRIDE
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(const std::string &fname)
std::map< std::string, NpyArray > npz_t
Definition vpIoTools.h:177
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT std::string getDateTime(const std::string &format="%Y/%m/%d %H:%M:%S")
std::shared_ptr< std::vector< char > > data_holder
Definition vpIoTools.h:169
std::vector< size_t > shape
Definition vpIoTools.h:170