39#include <visp3/core/vpConfig.h>
41#if defined(VISP_HAVE_THREADS) && defined(VISP_HAVE_DISPLAY)
42#include <condition_variable>
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>
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>
63#if defined(VISP_HAVE_PCL_IO)
64#include <pcl/io/pcd_io.h>
68#ifdef ENABLE_VISP_NAMESPACE
74void usage(
const char *argv[],
int error)
76 std::cout <<
"\nNAME " << std::endl
78 <<
" - Replay data (color, depth, infrared, point cloud) acquired" << std::endl
79 <<
" with a Realsense device using visp-save-rs-dataset app." << std::endl;
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;
85 std::cout <<
"\nSYNOPSIS " << std::endl
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]"
93 <<
" [--fps,-f <framerate>]"
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
101 <<
" --pattern,-e <filename numbering pattern (e.g. %06d)>" << std::endl
102 <<
" Filename numbering pattern used when saving data." << 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
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."
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
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
121 <<
" --fps,-f <framerate>" << std::endl
122 <<
" Framerate in Hz used to playback the dataset." << std::endl
123 <<
" Default: 30 fps" << std::endl
125 <<
" --help,-h" << std::endl
126 <<
" Display this helper message." << std::endl
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
135 std::cout <<
"Error" << std::endl
137 <<
"Unsupported parameter " << argv[
error] << std::endl;
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)
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]);
148 else if (((std::string(argv[i]) ==
"--pattern") || (std::string(argv[i]) ==
"-e")) && (i + 1 < argc)) {
149 numbering_pattern = std::string(argv[++i]);
151 else if ((std::string(argv[i]) ==
"--step-by-step") || (std::string(argv[i]) ==
"-s")) {
154 else if ((std::string(argv[i]) ==
"--save-video") || (std::string(argv[i]) ==
"-o")) {
157 else if ((std::string(argv[i]) ==
"--display-colored-depth") || (std::string(argv[i]) ==
"-colored-depth")) {
158 display_colored_depth =
true;
160 else if ((std::string(argv[i]) ==
"--loop") || (std::string(argv[i]) ==
"-l")) {
163 else if (((std::string(argv[i]) ==
"--fps") || (std::string(argv[i]) ==
"-f")) && (i + 1 < argc)) {
164 fps = std::atof(argv[++i]);
166 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
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)
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) {
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");
208 for (
size_t i = 0;
i < ext.size(); ++
i) {
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);
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");
239#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_IO) && defined(VISP_HAVE_PCL_COMMON)
240 ext.push_back(
".pcd");
242 for (
size_t i = 0;
i < ext.size(); ++
i) {
256 g.
setFileName(input_folder +
"/color_image_" + input_pattern + color_ext);
258 else if (infra_found) {
259 g.
setFileName(input_folder +
"/infrared_image_" + input_pattern + infra_ext);
262 std::cout <<
"WARNING: Unable to find first and last frame index images" << std::endl;
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,
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
293#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
299#
if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
303 std::cerr <<
"End of sequence." << std::endl;
317 if (depth_ext ==
".bin") {
318 std::ifstream file_depth(filename_depth.c_str(), std::ios::in | std::ios::binary);
319 if (file_depth.is_open()) {
323 I_depth_raw.
resize(height, width);
325 uint16_t depth_value = 0;
326 for (
unsigned int i = 0;
i <
height;
i++) {
327 for (
unsigned int j = 0;
j <
width;
j++) {
329 I_depth_raw[
i][
j] = depth_value;
334 else if (depth_ext ==
".npz") {
335#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
344 uint16_t *depth_data_ptr = arr_depth_data.
data<uint16_t>();
345 assert(arr_depth_data.
shape.size() == 3);
346 assert(arr_depth_data.
shape[2] == 1);
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;
368#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
371 if (pcl_ext ==
".npz") {
372#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX)
381 float *pcl_data_ptr = arr_pcl_data.
data<
float>();
382 assert(arr_pcl_data.
shape.size() == 3);
383 assert(arr_pcl_data.
shape[2] == 3);
386 const char is_dense = 1;
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));
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];
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;
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;
418 const char is_dense = 1;
421 file_pointcloud.read((
char *)(&is_dense),
sizeof(is_dense));
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));
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++) {
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;
449int main(
int argc,
const char *argv[])
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;
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)) {
469#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
479 bool init_display =
false;
481#if defined(VISP_HAVE_PCL)
483 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud(
new pcl::PointCloud<pcl::PointXYZ>());
484#if defined(VISP_HAVE_PCL_VISUALIZATION)
492 if (opt_save_video) {
494 writer.
setFileName(output_folder +
"/" + opt_input_pattern +
".png");
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;
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,
510 frame_first, frame_last);
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;
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;
531 if (!color_found && !depth_found && !infra_found && !pcl_found) {
532 std::cout <<
"\nError: No data found in " << opt_input_folder <<
" folder" << std::endl;
536 std::string filename_color, filename_depth, filename_infra, filename_pcl;
540#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON)
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);
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);
560 if (opt_display_colored_depth) {
570 d1->init(I_color, 0, 0,
"Color image");
573 if (opt_display_colored_depth) {
574 d2->init(I_depth_color, I_color.
getWidth() + 80, 0,
"Depth image");
577 d2->init(I_depth_gray, I_color.
getWidth() + 80, 0,
"Depth image");
581 d3->init(I_infra, I_color.
getWidth() + 80, I_color.
getHeight() + 70,
"Infrared image");
583#if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_VISUALIZATION)
585 if (pointcloud->size() > 0) {
588 pcl_viewer.
startThread(std::ref(mutex), pointcloud);
596 if (opt_step_by_step) {
604 if (opt_display_colored_depth) {
616 if (opt_display_colored_depth) {
624 if (opt_save_video) {
631 if (!opt_display_colored_depth) {
643 quit = !opt_step_by_step;
647 opt_step_by_step = !opt_step_by_step;
658 if (cpt_frame == frame_last) {
659 std::cout <<
"End of sequence reached" << std::endl;
660 cpt_frame = frame_first;
665#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
682 std::cerr <<
"Enable C++11 or higher (cmake -DUSE_CXX_STANDARD=11) and install X11 or GDI!" << std::endl;
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.
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)
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.
unsigned int getWidth() const
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
void insert(const vpImage< Type > &src, const vpImagePoint &topLeft)
unsigned int getSize() const
unsigned int getHeight() const
Error that can be emitted by the vpIoTools class and its derivatives.
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
void open(vpImage< vpRGBa > &I) VP_OVERRIDE
void setFileName(const std::string &filename)
long getFirstFrameIndex()
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
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
std::vector< size_t > shape