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