2 #include <visp3/core/vpImage.h>
3 #include <visp3/gui/vpDisplayGDI.h>
4 #include <visp3/gui/vpDisplayOpenCV.h>
5 #include <visp3/gui/vpDisplayX.h>
6 #include <visp3/io/vpImageStorageWorker.h>
7 #include <visp3/sensor/vpRealSense.h>
8 #include <visp3/sensor/vpRealSense2.h>
10 void usage(
const char *argv[],
int error)
12 std::cout <<
"SYNOPSIS" << std::endl
13 <<
" " << argv[0] <<
" [--fps <6|15|30|60>]"
14 <<
" [--width <image width>]"
15 <<
" [--height <image height>]"
16 <<
" [--seqname <sequence name>]"
17 <<
" [--record <mode>]"
19 <<
" [--help] [-h]" << std::endl
21 std::cout <<
"DESCRIPTION" << std::endl
22 <<
" --fps <6|15|30|60>" << std::endl
23 <<
" Frames per second." << std::endl
24 <<
" Default: 30." << std::endl
26 <<
" --width <image width>" << std::endl
27 <<
" Default: 640." << std::endl
29 <<
" --height <image height>" << std::endl
30 <<
" Default: 480." << std::endl
32 <<
" --seqname <sequence name>" << std::endl
33 <<
" Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl
34 <<
" Default: empty." << std::endl
36 <<
" --record <mode>" << std::endl
37 <<
" Allowed values for mode are:" << std::endl
38 <<
" 0: record all the captures images (continuous mode)," << std::endl
39 <<
" 1: record only images selected by a user click (single shot mode)." << std::endl
40 <<
" Default mode: 0" << std::endl
42 <<
" --no-display" << std::endl
43 <<
" Disable displaying captured images." << std::endl
44 <<
" When used and sequence name specified, record mode is internally set to 1 (continuous mode)."
47 <<
" --help, -h" << std::endl
48 <<
" Print this helper message." << std::endl
50 std::cout <<
"USAGE" << std::endl
51 <<
" Example to visualize images:" << std::endl
52 <<
" " << argv[0] << std::endl
54 <<
" Examples to record a sequence of successive images in 640x480 resolution:" << std::endl
55 <<
" " << argv[0] <<
" --seqname I%04d.png" << std::endl
56 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 0" << std::endl
58 <<
" Examples to record single shot 640x480 images:\n"
59 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1\n"
60 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 1" << std::endl
62 <<
" Examples to record single shot 1280x720 images:\n"
63 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1 --width 1280 --height 720" << std::endl
67 std::cout <<
"Error" << std::endl
69 <<
"Unsupported parameter " << argv[error] << std::endl;
76 int main(
int argc,
const char *argv[])
78 #if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS)
80 std::string opt_seqname;
81 int opt_record_mode = 0;
83 bool opt_display =
true;
84 unsigned int opt_width = 640;
85 unsigned int opt_height = 480;
87 for (
int i = 1; i < argc; i++) {
88 if (std::string(argv[i]) ==
"--fps") {
89 opt_fps = std::atoi(argv[i + 1]);
92 else if (std::string(argv[i]) ==
"--seqname") {
93 opt_seqname = std::string(argv[i + 1]);
96 else if (std::string(argv[i]) ==
"--width") {
97 opt_width = std::atoi(argv[i + 1]);
100 else if (std::string(argv[i]) ==
"--height") {
101 opt_height = std::atoi(argv[i + 1]);
104 else if (std::string(argv[i]) ==
"--record") {
105 opt_record_mode = std::atoi(argv[i + 1]);
108 else if (std::string(argv[i]) ==
"--no-display") {
111 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
121 if ((!opt_display) && (!opt_seqname.empty())) {
125 if (opt_fps != 6 && opt_fps != 15 && opt_fps != 30 && opt_fps != 60) {
128 std::cout <<
"Resolution : " << opt_width <<
" x " << opt_height << std::endl;
129 std::cout <<
"Recording : " << (opt_seqname.empty() ?
"disabled" :
"enabled") << std::endl;
130 std::cout <<
"Framerate : " << opt_fps << std::endl;
131 std::cout <<
"Display : " << (opt_display ?
"enabled" :
"disabled") << std::endl;
133 std::string text_record_mode =
134 std::string(
"Record mode: ") + (opt_record_mode ? std::string(
"single") : std::string(
"continuous"));
136 if (!opt_seqname.empty()) {
137 std::cout << text_record_mode << std::endl;
138 std::cout <<
"Record name: " << opt_seqname << std::endl;
142 #ifdef VISP_HAVE_REALSENSE2
143 std::cout <<
"SDK : Realsense 2" << std::endl;
146 config.disable_stream(RS2_STREAM_DEPTH);
147 config.disable_stream(RS2_STREAM_INFRARED);
148 config.enable_stream(RS2_STREAM_COLOR, opt_width, opt_height, RS2_FORMAT_RGBA8, opt_fps);
151 std::cout <<
"SDK : Realsense 1" << std::endl;
158 std::cout <<
"Image size : " << I.
getWidth() <<
" " << I.
getHeight() << std::endl;
162 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
163 std::cout <<
"No image viewer is available..." << std::endl;
170 #elif defined(VISP_HAVE_GDI)
172 #elif defined(HAVE_OPENCV_HIGHGUI)
188 quit = image_queue.record(I);
190 std::stringstream ss;
195 image_queue.cancel();
196 image_storage_thread.join();
203 std::cout <<
"Catch an exception: " << e << std::endl;
208 #if !(defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2))
209 std::cout <<
"Install librealsense version > 2.31.0, configure and build ViSP again to use this example" << std::endl;
211 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
212 std::cout <<
"This tutorial should be built with c++11 support" << std::endl;
Display for windows using GDI (available on any windows 32 platform).
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Class that defines generic functionalities for display.
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)
error that can be emitted by ViSP classes.
unsigned int getWidth() const
unsigned int getHeight() const
bool open(const rs2::config &cfg=rs2::config())
void setStreamSettings(const rs::stream &stream, const rs::preset &preset)
void acquire(std::vector< vpColVector > &pointcloud)
VISP_EXPORT double measureTimeMs()