MRPT  1.9.9
test.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2018, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
12 #include <mrpt/system/filesystem.h> // for ASSERT_FILE_EXISTS_
14 #include <iostream>
15 
16 using namespace mrpt;
17 using namespace mrpt::gui;
18 using namespace mrpt::vision;
19 using namespace mrpt::opengl;
20 using namespace mrpt::system;
21 using namespace mrpt::vision;
22 using namespace std;
23 
24 // ------------------------------------------------------
25 // TestStereoCalibrate
26 // ------------------------------------------------------
27 int TestStereoCalibrate(int argc, char** argv)
28 {
29  CTimeLogger timlog;
30 
31  // Parse optional arguments:
32  if (argc == 1 || ((argc - 1) & 1) != 0)
33  {
34  cout << "Usage:\n"
35  << argv[0] << "left_image1 right_image1 [L2 R2] [L3 R3] [...]\n";
36  return -1;
37  }
38 
39  // The stereo calibration structures:
40  TCalibrationStereoImageList calib_imgs;
41  TStereoCalibResults calib_result;
42  TStereoCalibParams calib_params;
43 
44  // ============ Set parameters ============
45  calib_params.check_size_x = 7;
46  calib_params.check_size_y = 9;
47  calib_params.check_squares_length_X_meters = 22.83e-3;
48  calib_params.check_squares_length_Y_meters = 24.31e-3;
49  // calib_params.maxIters = 300;
50  // calib_params.verbose = true;
51  calib_params.optimize_k1 = true;
52  calib_params.optimize_k2 = true;
53 
54  // Load images:
55  const size_t nPairs = (argc >> 1);
56  for (size_t i = 0; i < nPairs; i++)
57  {
58  const string sImgL = argv[1 + 2 * i + 0];
59  const string sImgR = argv[1 + 2 * i + 1];
60  ASSERT_FILE_EXISTS_(sImgL);
61  ASSERT_FILE_EXISTS_(sImgR);
62 
63  calib_imgs.resize(calib_imgs.size() + 1);
64  TImageStereoCalibData& stereo_dat = *calib_imgs.rbegin();
65 
66 #if 1
67  // Load all images in memory:
68  if (!stereo_dat.left.img_original.loadFromFile(sImgL))
69  THROW_EXCEPTION_FMT("Error loading: %s", sImgL.c_str())
70  if (!stereo_dat.right.img_original.loadFromFile(sImgR))
71  THROW_EXCEPTION_FMT("Error loading: %s", sImgR.c_str())
72 #else
73  // Don't load images in memory until really needed.
74  stereo_dat.left.img_original.setExternalStorage(sImgL);
75  stereo_dat.right.img_original.setExternalStorage(sImgR);
76 #endif
77  }
78 
79  // Run calibration:
81  calib_imgs, calib_params, calib_result);
82 
83  if (!res)
84  {
85  std::cout << "Calibration returned an error status.\n";
86  return -1;
87  }
88  else
89  {
90  // Calibration was OK:
91 
92  // Show detected corners:
93  if (1)
94  {
95  mrpt::gui::CDisplayWindow3D win("Calibration results", 1000, 480);
96 
98  {
100  win.get3DSceneAndLock();
101  view1 = scene->getViewport("main");
102  view2 = scene->createViewport("right");
103 
104  // Split viewing area into two halves:
105  view1->setViewportPosition(0, 0, 0.5, 1.0);
106  view2->setViewportPosition(0.5, 0, 0.5, 1.0);
107 
108  win.unlockAccess3DScene();
109  }
110 
111  for (size_t i = 0; i < nPairs; i++)
112  {
113  win.get3DSceneAndLock();
114 
115  view1->setImageView(
116  calib_imgs[i].left.img_rectified); // img_checkboard );
117  view2->setImageView(
118  calib_imgs[i].right.img_rectified); // img_checkboard );
119 
120  win.setWindowTitle(
121  mrpt::format(
122  "Detected corners: %u / %u",
123  static_cast<unsigned int>(i + 1),
124  static_cast<unsigned int>(nPairs)));
125 
126  win.unlockAccess3DScene();
127  win.repaint();
128 
129  win.waitForKey();
130  }
131  } // end show detected corners
132 
133  return 0;
134  }
135 }
136 
137 // ------------------------------------------------------
138 // MAIN
139 // ------------------------------------------------------
140 int main(int argc, char** argv)
141 {
142  try
143  {
144  return TestStereoCalibrate(argc, argv);
145  }
146  catch (std::exception& e)
147  {
148  std::cout << "MRPT exception caught: " << e.what() << std::endl;
149  return -1;
150  }
151  catch (...)
152  {
153  printf("Untyped exception!!");
154  return -1;
155  }
156 }
bool optimize_k1
Select which distortion parameters (of both left/right cameras) will be optimzed: k1...
Data associated to each stereo image in the calibration process mrpt::vision::checkerBoardCameraCalib...
void setExternalStorage(const std::string &fileName) noexcept
By using this method the image is marked as referenced to an external file, which will be loaded only...
Definition: CImage.cpp:1887
STL namespace.
double check_squares_length_X_meters
The size of each square in the checkerboard, in meters, in the "X" & Y" axes.
bool loadFromFile(const std::string &fileName, int isColor=-1)
Load image from a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:271
Input parameters for mrpt::vision::checkerBoardStereoCalibration.
Classes for computer vision, detectors, features, etc.
Definition: CCamModel.h:18
mrpt::gui::CDisplayWindow3D::Ptr win
unsigned int check_size_x
The number of squares in the checkerboard in the "X" & "Y" direction.
bool checkerBoardStereoCalibration(TCalibrationStereoImageList &images, const TStereoCalibParams &params, TStereoCalibResults &out_results)
Optimize the calibration parameters of a stereo camera or a RGB+D (Kinect) camera.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:16
int TestStereoCalibrate(int argc, char **argv)
The namespace for 3D scene representation and rendering.
Definition: CGlCanvasBase.h:15
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
GLuint res
Definition: glext.h:7268
Output results for mrpt::vision::checkerBoardStereoCalibration.
#define ASSERT_FILE_EXISTS_(FIL)
Definition: filesystem.h:21
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
Definition: exceptions.h:43
mrpt::img::CImage img_original
This image will be automatically loaded from the file name passed to checkerBoardCameraCalibration.
std::vector< TImageStereoCalibData > TCalibrationStereoImageList
A list of images, used in checkerBoardStereoCalibration.
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020