2 #include <visp3/core/vpConfig.h>
3 #include <visp3/core/vpImage.h>
4 #include <visp3/core/vpXmlParserCamera.h>
5 #include <visp3/gui/vpDisplayGDI.h>
6 #include <visp3/gui/vpDisplayOpenCV.h>
7 #include <visp3/gui/vpDisplayX.h>
8 #include <visp3/io/vpImageStorageWorker.h>
9 #include <visp3/sensor/vpRealSense.h>
10 #include <visp3/sensor/vpRealSense2.h>
12 void usage(
const char *argv[],
int error)
14 std::cout <<
"SYNOPSIS" << std::endl
15 <<
" " << argv[0] <<
" [--fps <6|15|30|60>]"
16 <<
" [--width <image width>]"
17 <<
" [--height <image height>]"
18 <<
" [--seqname <sequence name>]"
19 <<
" [--record <mode>]"
21 <<
" [--help] [-h]" << std::endl
23 std::cout <<
"DESCRIPTION" << std::endl
24 <<
" --fps <6|15|30|60>" << std::endl
25 <<
" Frames per second." << std::endl
26 <<
" Default: 30." << std::endl
28 <<
" --width <image width>" << std::endl
29 <<
" Default: 640." << std::endl
31 <<
" --height <image height>" << std::endl
32 <<
" Default: 480." << std::endl
34 <<
" --seqname <sequence name>" << std::endl
35 <<
" Name of the sequence of image to create (ie: /tmp/image%04d.jpg)." << std::endl
36 <<
" Default: empty." << std::endl
38 <<
" --record <mode>" << std::endl
39 <<
" Allowed values for mode are:" << std::endl
40 <<
" 0: record all the captures images (continuous mode)," << std::endl
41 <<
" 1: record only images selected by a user click (single shot mode)." << std::endl
42 <<
" Default mode: 0" << std::endl
44 <<
" --no-display" << std::endl
45 <<
" Disable displaying captured images." << std::endl
46 <<
" When used and sequence name specified, record mode is internally set to 1 (continuous mode)."
49 <<
" --help, -h" << std::endl
50 <<
" Print this helper message." << std::endl
52 std::cout <<
"USAGE" << std::endl
53 <<
" Example to visualize images:" << std::endl
54 <<
" " << argv[0] << std::endl
56 <<
" Examples to record a sequence of successive images in 640x480 resolution:" << std::endl
57 <<
" " << argv[0] <<
" --seqname I%04d.png" << std::endl
58 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 0" << std::endl
60 <<
" Examples to record single shot 640x480 images:\n"
61 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1\n"
62 <<
" " << argv[0] <<
" --seqname folder/I%04d.png --record 1" << std::endl
64 <<
" Examples to record single shot 1280x720 images:\n"
65 <<
" " << argv[0] <<
" --seqname I%04d.png --record 1 --width 1280 --height 720" << std::endl
69 std::cout <<
"Error" << std::endl
71 <<
"Unsupported parameter " << argv[error] << std::endl;
78 int main(
int argc,
const char *argv[])
80 #if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS)
81 #ifdef ENABLE_VISP_NAMESPACE
85 std::string opt_seqname;
86 int opt_record_mode = 0;
88 bool opt_display =
true;
89 unsigned int opt_width = 640;
90 unsigned int opt_height = 480;
92 for (
int i = 1; i < argc; i++) {
93 if (std::string(argv[i]) ==
"--fps") {
94 opt_fps = std::atoi(argv[i + 1]);
97 else if (std::string(argv[i]) ==
"--seqname") {
98 opt_seqname = std::string(argv[i + 1]);
101 else if (std::string(argv[i]) ==
"--width") {
102 opt_width = std::atoi(argv[i + 1]);
105 else if (std::string(argv[i]) ==
"--height") {
106 opt_height = std::atoi(argv[i + 1]);
109 else if (std::string(argv[i]) ==
"--record") {
110 opt_record_mode = std::atoi(argv[i + 1]);
113 else if (std::string(argv[i]) ==
"--no-display") {
116 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
126 if ((!opt_display) && (!opt_seqname.empty())) {
130 if (opt_fps != 6 && opt_fps != 15 && opt_fps != 30 && opt_fps != 60) {
133 std::cout <<
"Resolution : " << opt_width <<
" x " << opt_height << std::endl;
134 std::cout <<
"Recording : " << (opt_seqname.empty() ?
"disabled" :
"enabled") << std::endl;
135 std::cout <<
"Framerate : " << opt_fps << std::endl;
136 std::cout <<
"Display : " << (opt_display ?
"enabled" :
"disabled") << std::endl;
138 std::string text_record_mode =
139 std::string(
"Record mode: ") + (opt_record_mode ? std::string(
"single") : std::string(
"continuous"));
141 if (!opt_seqname.empty()) {
142 std::cout << text_record_mode << std::endl;
143 std::cout <<
"Record name: " << opt_seqname << std::endl;
147 #ifdef VISP_HAVE_REALSENSE2
148 std::cout <<
"SDK : Realsense 2" << std::endl;
151 config.disable_stream(RS2_STREAM_DEPTH);
152 config.disable_stream(RS2_STREAM_INFRARED);
153 config.enable_stream(RS2_STREAM_COLOR, opt_width, opt_height, RS2_FORMAT_RGBA8, opt_fps);
156 std::cout <<
"SDK : Realsense 1" << std::endl;
163 std::cout <<
"Image size : " << I.
getWidth() <<
" " << I.
getHeight() << std::endl;
170 std::cout <<
"Create output folder: " << output_folder << std::endl;
178 std::string cam_filename = output_folder +
"/camera.xml";
180 std::cout <<
"Save camera intrinsics in: " << cam_filename << std::endl;
181 if (p.
save(cam, cam_filename,
"camera")) {
182 std::cout <<
"Cannot save camera parameters in " << cam_filename << std::endl;
187 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
188 std::cout <<
"No image viewer is available..." << std::endl;
194 d =
new vpDisplayX(I);
195 #elif defined(VISP_HAVE_GDI)
197 #elif defined(HAVE_OPENCV_HIGHGUI)
202 vpImageQueue<vpRGBa> image_queue(opt_seqname, opt_record_mode);
213 quit = image_queue.record(I);
215 std::stringstream ss;
220 image_queue.cancel();
221 image_storage_thread.join();
228 std::cout <<
"Catch an exception: " << e << std::endl;
233 #if !(defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2))
234 std::cout <<
"Install librealsense version > 2.31.0, configure and build ViSP again to use this example" << std::endl;
236 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
237 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...
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()