2 #include <visp3/core/vpImage.h>
3 #include <visp3/core/vpXmlParserCamera.h>
4 #include <visp3/gui/vpDisplayGDI.h>
5 #include <visp3/gui/vpDisplayOpenCV.h>
6 #include <visp3/gui/vpDisplayX.h>
7 #include <visp3/io/vpImageStorageWorker.h>
8 #include <visp3/sensor/vpRealSense.h>
9 #include <visp3/sensor/vpRealSense2.h>
11 void usage(
const char *argv[],
int error)
13 std::cout <<
"SYNOPSIS" << std::endl
14 <<
" " << argv[0] <<
" [--fps <6|15|30|60>]"
15 <<
" [--width <image width>]"
16 <<
" [--height <image height>]"
17 <<
" [--seqname <sequence name>]"
18 <<
" [--record <mode>]"
20 <<
" [--help] [-h]" << std::endl
22 std::cout <<
"DESCRIPTION" << std::endl
23 <<
" --fps <6|15|30|60>" << std::endl
24 <<
" Frames per second." << std::endl
25 <<
" Default: 30." << std::endl
27 <<
" --width <image width>" << std::endl
28 <<
" Default: 640." << std::endl
30 <<
" --height <image height>" << std::endl
31 <<
" Default: 480." << std::endl
33 <<
" --seqname <sequence name>" << std::endl
34 <<
" Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl
35 <<
" Default: empty." << std::endl
37 <<
" --record <mode>" << std::endl
38 <<
" Allowed values for mode are:" << std::endl
39 <<
" 0: record all the captures images (continuous mode)," << std::endl
40 <<
" 1: record only images selected by a user click (single shot mode)." << std::endl
41 <<
" Default mode: 0" << std::endl
43 <<
" --no-display" << std::endl
44 <<
" Disable displaying captured images." << std::endl
45 <<
" When used and sequence name specified, record mode is internally set to 1 (continuous mode)."
48 <<
" --help, -h" << std::endl
49 <<
" Print this helper message." << std::endl
51 std::cout <<
"USAGE" << std::endl
52 <<
" Example to visualize images:" << std::endl
53 <<
" " << argv[0] << std::endl
55 <<
" Examples to record a sequence of successive images in 640x480 resolution:" << std::endl
56 <<
" " << argv[0] <<
" --seqname I%04d.png" << std::endl
57 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 0" << std::endl
59 <<
" Examples to record single shot 640x480 images:\n"
60 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1\n"
61 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 1" << std::endl
63 <<
" Examples to record single shot 1280x720 images:\n"
64 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1 --width 1280 --height 720" << std::endl
68 std::cout <<
"Error" << std::endl
70 <<
"Unsupported parameter " << argv[error] << std::endl;
77 int main(
int argc,
const char *argv[])
79 #if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS)
81 std::string opt_seqname;
82 int opt_record_mode = 0;
84 bool opt_display =
true;
85 unsigned int opt_width = 640;
86 unsigned int opt_height = 480;
88 for (
int i = 1; i < argc; i++) {
89 if (std::string(argv[i]) ==
"--fps") {
90 opt_fps = std::atoi(argv[i + 1]);
93 else if (std::string(argv[i]) ==
"--seqname") {
94 opt_seqname = std::string(argv[i + 1]);
97 else if (std::string(argv[i]) ==
"--width") {
98 opt_width = std::atoi(argv[i + 1]);
101 else if (std::string(argv[i]) ==
"--height") {
102 opt_height = std::atoi(argv[i + 1]);
105 else if (std::string(argv[i]) ==
"--record") {
106 opt_record_mode = std::atoi(argv[i + 1]);
109 else if (std::string(argv[i]) ==
"--no-display") {
112 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
122 if ((!opt_display) && (!opt_seqname.empty())) {
126 if (opt_fps != 6 && opt_fps != 15 && opt_fps != 30 && opt_fps != 60) {
129 std::cout <<
"Resolution : " << opt_width <<
" x " << opt_height << std::endl;
130 std::cout <<
"Recording : " << (opt_seqname.empty() ?
"disabled" :
"enabled") << std::endl;
131 std::cout <<
"Framerate : " << opt_fps << std::endl;
132 std::cout <<
"Display : " << (opt_display ?
"enabled" :
"disabled") << std::endl;
134 std::string text_record_mode =
135 std::string(
"Record mode: ") + (opt_record_mode ? std::string(
"single") : std::string(
"continuous"));
137 if (!opt_seqname.empty()) {
138 std::cout << text_record_mode << std::endl;
139 std::cout <<
"Record name: " << opt_seqname << std::endl;
143 #ifdef VISP_HAVE_REALSENSE2
144 std::cout <<
"SDK : Realsense 2" << std::endl;
147 config.disable_stream(RS2_STREAM_DEPTH);
148 config.disable_stream(RS2_STREAM_INFRARED);
149 config.enable_stream(RS2_STREAM_COLOR, opt_width, opt_height, RS2_FORMAT_RGBA8, opt_fps);
152 std::cout <<
"SDK : Realsense 1" << std::endl;
159 std::cout <<
"Image size : " << I.
getWidth() <<
" " << I.
getHeight() << std::endl;
166 std::cout <<
"Create output folder: " << output_folder << std::endl;
174 std::string cam_filename = output_folder +
"/camera.xml";
176 std::cout <<
"Save camera intrinsics in: " << cam_filename << std::endl;
177 if (p.
save(cam, cam_filename,
"camera")) {
178 std::cout <<
"Cannot save camera parameters in " << cam_filename << std::endl;
183 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
184 std::cout <<
"No image viewer is available..." << std::endl;
191 #elif defined(VISP_HAVE_GDI)
193 #elif defined(HAVE_OPENCV_HIGHGUI)
209 quit = image_queue.record(I);
211 std::stringstream ss;
216 image_queue.cancel();
217 image_storage_thread.join();
224 std::cout <<
"Catch an exception: " << e << std::endl;
229 #if !(defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2))
230 std::cout <<
"Install librealsense version > 2.31.0, configure and build ViSP again to use this example" << std::endl;
232 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
233 std::cout <<
"This tutorial should be built with c++11 support" << std::endl;
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
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.
const std::string & getStringMessage() const
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)
vpCameraParameters getCameraParameters(const rs::stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion) const
void acquire(std::vector< vpColVector > &pointcloud)
XML parser to load and save intrinsic camera parameters.
int save(const vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, unsigned int image_width=0, unsigned int image_height=0, const std::string &additionalInfo="", bool verbose=true)
VISP_EXPORT double measureTimeMs()