Visual Servoing Platform  version 3.6.1 under development (2024-04-16)
tutorial-grabber-realsense.cpp
1 
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>
10 
11 void usage(const char *argv[], int error)
12 {
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>]"
19  << " [--no-display]"
20  << " [--help] [-h]" << std::endl
21  << 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
26  << std::endl
27  << " --width <image width>" << std::endl
28  << " Default: 640." << std::endl
29  << std::endl
30  << " --height <image height>" << std::endl
31  << " Default: 480." << std::endl
32  << 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
36  << 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
42  << 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)."
46  << std::endl
47  << std::endl
48  << " --help, -h" << std::endl
49  << " Print this helper message." << std::endl
50  << std::endl;
51  std::cout << "USAGE" << std::endl
52  << " Example to visualize images:" << std::endl
53  << " " << argv[0] << std::endl
54  << 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
58  << 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
62  << 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
65  << std::endl;
66 
67  if (error) {
68  std::cout << "Error" << std::endl
69  << " "
70  << "Unsupported parameter " << argv[error] << std::endl;
71  }
72 }
73 
77 int main(int argc, const char *argv[])
78 {
79 #if defined(VISP_HAVE_REALSENSE) || defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_THREADS)
80  try {
81  std::string opt_seqname;
82  int opt_record_mode = 0;
83  int opt_fps = 30;
84  bool opt_display = true;
85  unsigned int opt_width = 640;
86  unsigned int opt_height = 480;
87 
88  for (int i = 1; i < argc; i++) {
89  if (std::string(argv[i]) == "--fps") {
90  opt_fps = std::atoi(argv[i + 1]);
91  i++;
92  }
93  else if (std::string(argv[i]) == "--seqname") {
94  opt_seqname = std::string(argv[i + 1]);
95  i++;
96  }
97  else if (std::string(argv[i]) == "--width") {
98  opt_width = std::atoi(argv[i + 1]);
99  i++;
100  }
101  else if (std::string(argv[i]) == "--height") {
102  opt_height = std::atoi(argv[i + 1]);
103  i++;
104  }
105  else if (std::string(argv[i]) == "--record") {
106  opt_record_mode = std::atoi(argv[i + 1]);
107  i++;
108  }
109  else if (std::string(argv[i]) == "--no-display") {
110  opt_display = false;
111  }
112  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
113  usage(argv, 0);
114  return EXIT_SUCCESS;
115  }
116  else {
117  usage(argv, i);
118  return EXIT_FAILURE;
119  }
120  }
121 
122  if ((!opt_display) && (!opt_seqname.empty())) {
123  opt_record_mode = 0;
124  }
125 
126  if (opt_fps != 6 && opt_fps != 15 && opt_fps != 30 && opt_fps != 60) {
127  opt_fps = 30; // Default
128  }
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;
133 
134  std::string text_record_mode =
135  std::string("Record mode: ") + (opt_record_mode ? std::string("single") : std::string("continuous"));
136 
137  if (!opt_seqname.empty()) {
138  std::cout << text_record_mode << std::endl;
139  std::cout << "Record name: " << opt_seqname << std::endl;
140  }
141  vpImage<vpRGBa> I;
142 
143 #ifdef VISP_HAVE_REALSENSE2
144  std::cout << "SDK : Realsense 2" << std::endl;
145  vpRealSense2 g;
146  rs2::config config;
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);
150  g.open(config);
151 #else
152  std::cout << "SDK : Realsense 1" << std::endl;
153  vpRealSense g;
154  g.setStreamSettings(rs::stream::color, vpRealSense::vpRsStreamParams(opt_width, opt_height, rs::format::rgba8, 60));
155  g.open();
156 #endif
157  g.acquire(I);
158 
159  std::cout << "Image size : " << I.getWidth() << " " << I.getHeight() << std::endl;
160 
163  std::string output_folder = vpIoTools::getParent(opt_seqname);
164  if (!vpIoTools::checkDirectory(output_folder)) {
165  try {
166  std::cout << "Create output folder: " << output_folder << std::endl;
167  vpIoTools::makeDirectory(output_folder);
168  }
169  catch (const vpException &e) {
170  std::cout << e.getStringMessage();
171  return EXIT_FAILURE;
172  }
173  }
174  std::string cam_filename = output_folder + "/camera.xml";
175 
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;
179  }
180 
181  vpDisplay *d = nullptr;
182  if (opt_display) {
183 #if !(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV))
184  std::cout << "No image viewer is available..." << std::endl;
185  opt_display = false;
186 #endif
187  }
188  if (opt_display) {
189 #ifdef VISP_HAVE_X11
190  d = new vpDisplayX(I);
191 #elif defined(VISP_HAVE_GDI)
192  d = new vpDisplayGDI(I);
193 #elif defined(HAVE_OPENCV_HIGHGUI)
194  d = new vpDisplayOpenCV(I);
195 #endif
196  }
197 
198  vpImageQueue<vpRGBa> image_queue(opt_seqname, opt_record_mode);
199  vpImageStorageWorker<vpRGBa> image_storage_worker(std::ref(image_queue));
200  std::thread image_storage_thread(&vpImageStorageWorker<vpRGBa>::run, &image_storage_worker);
201 
202  bool quit = false;
203  while (!quit) {
204  double t = vpTime::measureTimeMs();
205  g.acquire(I);
206 
208 
209  quit = image_queue.record(I);
210 
211  std::stringstream ss;
212  ss << "Acquisition time: " << std::setprecision(3) << vpTime::measureTimeMs() - t << " ms";
213  vpDisplay::displayText(I, I.getHeight() - 20, 10, ss.str(), vpColor::red);
214  vpDisplay::flush(I);
215  }
216  image_queue.cancel();
217  image_storage_thread.join();
218 
219  if (d) {
220  delete d;
221  }
222  }
223  catch (const vpException &e) {
224  std::cout << "Catch an exception: " << e << std::endl;
225  }
226 #else
227  (void)argc;
228  (void)argv;
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;
231 #endif
232 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
233  std::cout << "This tutorial should be built with c++11 support" << std::endl;
234 #endif
235 #endif
236 }
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor red
Definition: vpColor.h:211
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
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...
Definition: vpDisplayX.h:128
Class that defines generic functionalities for display.
Definition: vpDisplay.h:173
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.
Definition: vpException.h:59
const std::string & getStringMessage() const
Definition: vpException.cpp:66
unsigned int getWidth() const
Definition: vpImage.h:245
unsigned int getHeight() const
Definition: vpImage.h:184
static bool checkDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:832
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:981
static std::string getParent(const std::string &pathname)
Definition: vpIoTools.cpp:2047
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()