Visual Servoing Platform  version 3.0.0
camera_calibration.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Camera calibration with chessboard or circle calibration grid.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 #include <iostream>
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #if VISP_HAVE_OPENCV_VERSION >= 0x020300
42 
43 #include <opencv2/core/core.hpp>
44 #include <opencv2/imgproc/imgproc.hpp>
45 #include <opencv2/calib3d/calib3d.hpp>
46 #include <opencv2/highgui/highgui.hpp>
47 
48 #include <visp3/vision/vpCalibration.h>
49 
50 #include <visp3/gui/vpDisplayX.h>
51 #include <visp3/gui/vpDisplayGDI.h>
52 #include <visp3/gui/vpDisplayOpenCV.h>
53 #include <visp3/gui/vpDisplayD3D.h>
54 #include <visp3/gui/vpDisplayGTK.h>
55 #include <visp3/core/vpIoTools.h>
56 #include <visp3/core/vpPoint.h>
57 #include <visp3/io/vpVideoReader.h>
58 #include <visp3/core/vpXmlParserCamera.h>
59 
60 #ifndef DOXYGEN_SHOULD_SKIP_THIS
61 
62 class Settings
63 {
64 public:
65  Settings()
66  : boardSize(), calibrationPattern(UNDEFINED), squareSize(0.), input(), tempo(0.), goodInput(false), patternToUse()
67  {
68  boardSize = cv::Size(0, 0);
69  calibrationPattern = UNDEFINED;
70  squareSize = 0.025f;
71  goodInput = false;
72  tempo = 1.f;
73 
74  }
75  enum Pattern { UNDEFINED, CHESSBOARD, CIRCLES_GRID};
76 
77  bool read(const std::string &filename) // Read the parameters
78  {
79  // reading configuration file
80  if (! vpIoTools::loadConfigFile(filename) )
81  return false;
82  vpIoTools::readConfigVar("BoardSize_Width:", boardSize.width);
83  vpIoTools::readConfigVar("BoardSize_Height:", boardSize.height);
84  vpIoTools::readConfigVar("Square_Size:", squareSize);
85  vpIoTools::readConfigVar("Calibrate_Pattern:", patternToUse);
86  vpIoTools::readConfigVar("Input:", input);
87  vpIoTools::readConfigVar("Tempo:", tempo);
88 
89  std::cout << "grid width : " << boardSize.width << std::endl;
90  std::cout << "grid height: " << boardSize.height << std::endl;
91  std::cout << "square size: " << squareSize << std::endl;
92  std::cout << "pattern : " << patternToUse << std::endl;
93  std::cout << "input seq : " << input << std::endl;
94  std::cout << "tempo : " << tempo << std::endl;
95  interprate();
96  return true;
97  }
98  void interprate()
99  {
100  goodInput = true;
101  if (boardSize.width <= 0 || boardSize.height <= 0) {
102  std::cerr << "Invalid Board size: " << boardSize.width << " " << boardSize.height << std::endl;
103  goodInput = false;
104  }
105  if (squareSize <= 10e-6) {
106  std::cerr << "Invalid square size " << squareSize << std::endl;
107  goodInput = false;
108  }
109 
110  if (input.empty()) // Check for valid input
111  goodInput = false;
112 
113  calibrationPattern = UNDEFINED;
114  if (patternToUse.compare("CHESSBOARD") == 0) calibrationPattern = CHESSBOARD;
115  else if (patternToUse.compare("CIRCLES_GRID") == 0) calibrationPattern = CIRCLES_GRID;
116  if (calibrationPattern == UNDEFINED) {
117  std::cerr << " Inexistent camera calibration mode: " << patternToUse << std::endl;
118  goodInput = false;
119  }
120  }
121 
122 public:
123  cv::Size boardSize; // The size of the board -> Number of items by width and height
124  Pattern calibrationPattern;// One of the Chessboard, circles, or asymmetric circle pattern
125  float squareSize; // The size of a square in your defined unit (point, millimeter,etc).
126  std::string input; // The input image sequence
127  float tempo; // Tempo in seconds between two images. If > 10 wait a click to continue
128  bool goodInput;
129 
130 private:
131  std::string patternToUse;
132 };
133 #endif
134 
135 int main(int argc, const char ** argv)
136 {
137  try {
138  std::string outputFileName = "camera.xml";
139 
140  Settings s;
141  const std::string inputSettingsFile = argc > 1 ? argv[1] : "default.cfg";
142  if (! s.read(inputSettingsFile) ) {
143  std::cout << "Could not open the configuration file: \"" << inputSettingsFile << "\"" << std::endl;
144  std::cout << std::endl << "Usage: " << argv[0] << " <configuration file>.cfg" << std::endl;
145  return -1;
146  }
147 
148  if (! s.goodInput)
149  {
150  std::cout << "Invalid input detected. Application stopping. " << std::endl;
151  return -1;
152  }
153 
154  // Start the calibration code
156  vpVideoReader reader;
157  reader.setFileName(s.input);
158  reader.open(I);
159 
160 #ifdef VISP_HAVE_X11
161  vpDisplayX d(I);
162 #elif defined VISP_HAVE_GDI
163  vpDisplayGDI d(I);
164 #elif defined VISP_HAVE_GTK
165  vpDisplayGTK d(I);
166 #elif defined VISP_HAVE_OPENCV
167  vpDisplayOpenCV d(I);
168 #endif
169 
170  std::vector<vpPoint> model;
171  std::vector<vpCalibration> calibrator;
172 
173  for (int i=0; i< s.boardSize.height; i++) {
174  for (int j=0; j< s.boardSize.width; j++) {
175  model.push_back( vpPoint(j*s.squareSize, i*s.squareSize, 0) );
176  }
177  }
178 
179  long frame_index;
180  while(! reader.end()) {
181  frame_index = reader.getFrameIndex();
182  reader.acquire(I);
184 
185  cv::Mat cvI;
186  std::vector<cv::Point2f> pointBuf;
187  vpImageConvert::convert(I, cvI);
188 
189  bool found = false;
190  switch( s.calibrationPattern ) // Find feature points on the input format
191  {
192  case Settings::CHESSBOARD:
193  //std::cout << "Use chessboard " << std::endl;
194  found = findChessboardCorners( cvI, s.boardSize, pointBuf,
195 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
196  cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_FAST_CHECK | cv::CALIB_CB_NORMALIZE_IMAGE);
197 #else
198  CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FAST_CHECK | CV_CALIB_CB_NORMALIZE_IMAGE);
199 #endif
200  break;
201  case Settings::CIRCLES_GRID:
202  //std::cout << "Use circle grid " << std::endl;
203  found = findCirclesGrid( cvI, s.boardSize, pointBuf, cv::CALIB_CB_SYMMETRIC_GRID );
204  break;
205  case Settings::UNDEFINED:
206  default:
207  std::cout << "Unkown calibration grid " << std::endl;
208  break;
209  }
210 
211  std::cout << "frame: " << frame_index << ", status: " << found;
212  if (!found)
213  std::cout << ", image rejected" << std::endl;
214  else
215  std::cout << ", image used as input data" << std::endl;
216 
217  if ( found) // If done with success,
218  {
219  std::vector<vpImagePoint> data;
220 
221  if (s.calibrationPattern == Settings::CHESSBOARD) {
222  // improve the found corners' coordinate accuracy for chessboard
223  cornerSubPix( cvI, pointBuf, cv::Size(11,11),
224  cv::Size(-1,-1),
225 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
226  cv::TermCriteria( cv::TermCriteria::EPS+cv::TermCriteria::COUNT, 30, 0.1 ));
227 #else
228  cv::TermCriteria( CV_TERMCRIT_EPS+CV_TERMCRIT_ITER, 30, 0.1 ));
229 #endif
230  }
231  char title[20]; sprintf(title, "image %ld", frame_index);
232  vpDisplay::setTitle(I, title);
233  for (unsigned int i=0; i < pointBuf.size(); i++) {
234  vpImagePoint ip(pointBuf[i].y, pointBuf[i].x);
235  data.push_back(ip);
237  }
238 
239  // Calibration on a single mono image
240  vpCalibration calib;
241  calib.setLambda(0.5);
242  calib.clearPoint();
243  for (unsigned int i=0; i<model.size(); i++) {
244  calib.addPoint(model[i].get_oX(), model[i].get_oY(), model[i].get_oZ(), data[i]);
245  }
247  vpCameraParameters cam;
248 
249  // Set (u0,v0) in the middle of the image
250  double px = cam.get_px();
251  double py = cam.get_px();
252  double u0 = I.getWidth()/2;
253  double v0 = I.getHeight()/2;
254  cam.initPersProjWithoutDistortion(px, py, u0, v0);
255 
256  if (calib.computeCalibration(vpCalibration::CALIB_VIRTUAL_VS, cMo, cam, false) == 0) {
257  //std::cout << "camera parameters: " << cam << std::endl;
258  calibrator.push_back(calib);
259  }
260  }
261 
262  if (found)
263  vpDisplay::displayText(I, 15, 15, "Image processing succeed", vpColor::green);
264  else
265  vpDisplay::displayText(I, 15, 15, "Image processing fails", vpColor::green);
266 
267  if (s.tempo > 10.f) {
268  vpDisplay::displayText(I, 35, 15, "A click to process the next image", vpColor::green);
269  vpDisplay::flush(I);
271  }
272  else {
273  vpDisplay::flush(I);
274  vpTime::wait(s.tempo*1000);
275  }
276  }
277 
278  // Now we consider the multi image calibration
279  // Calibrate by a non linear method based on virtual visual servoing
280  if (calibrator.empty()) {
281  std::cerr << "Unable to calibrate. Image processing failed !" << std::endl;
282  return 0;
283  }
284 
285  std::cout << "\nCalibration without distorsion in progress on " << calibrator.size() << " images..." << std::endl;
286  vpCameraParameters cam;
287  double error;
288  if (vpCalibration::computeCalibrationMulti(vpCalibration::CALIB_VIRTUAL_VS, calibrator, cam, error, false) == 0) {
289  std::cout << cam << std::endl;
290  std::cout << "Global reprojection error: " << error << std::endl;
291 #ifdef VISP_HAVE_XML2
292  vpXmlParserCamera xml;
293 
294  if(xml.save(cam, outputFileName.c_str(), "Camera", I.getWidth(), I.getHeight()) == vpXmlParserCamera::SEQUENCE_OK)
295  std::cout << "Camera parameters without distortion successfully saved in \"" << outputFileName << "\"" << std::endl;
296  else {
297  std::cout << "Failed to save the camera parameters without distortion in \"" << outputFileName << "\"" << std::endl;
298  std::cout << "A file with the same name exists. Remove it to be able to save the parameters..." << std::endl;
299  }
300 #endif
301  }
302  else
303  std::cout << "Calibration without distortion failed." << std::endl;
304 
305  std::cout << "\nCalibration with distorsion in progress on " << calibrator.size() << " images..." << std::endl;
306  if (vpCalibration::computeCalibrationMulti(vpCalibration::CALIB_VIRTUAL_VS_DIST, calibrator, cam, error, false) == 0) {
307  std::cout << cam << std::endl;
308  std::cout << "Global reprojection error: " << error << std::endl;
309 
310 #ifdef VISP_HAVE_XML2
311  vpXmlParserCamera xml;
312 
313  if(xml.save(cam, outputFileName.c_str(), "Camera", I.getWidth(), I.getHeight()) == vpXmlParserCamera::SEQUENCE_OK)
314  std::cout << "Camera parameters without distortion successfully saved in \"" << outputFileName << "\"" << std::endl;
315  else {
316  std::cout << "Failed to save the camera parameters without distortion in \"" << outputFileName << "\"" << std::endl;
317  std::cout << "A file with the same name exists. Remove it to be able to save the parameters..." << std::endl;
318  }
319 #endif
320  std::cout << std::endl;
321  for (unsigned int i=0; i<calibrator.size(); i++)
322  std::cout << "Estimated pose on input data " << i << ": " << vpPoseVector(calibrator[i].cMo_dist).t() << std::endl;
323 
324  }
325  else
326  std::cout << "Calibration with distortion failed." << std::endl;
327 
328  return 0;
329  }
330  catch(vpException e) {
331  std::cout << "Catch an exception: " << e << std::endl;
332  return 1;
333  }
334 }
335 #else
336 int main()
337 {
338  std::cout << "OpenCV 2.3.0 or higher is requested to run the calibration." << std::endl;
339 }
340 #endif
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:150
long getFrameIndex() const
unsigned int getWidth() const
Definition: vpImage.h:161
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
int computeCalibration(vpCalibrationMethodType method, vpHomogeneousMatrix &cMo_est, vpCameraParameters &cam_est, bool verbose=false)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Definition: vpDisplay.cpp:888
Define the X11 console to display images.
Definition: vpDisplayX.h:148
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
error that can be emited by ViSP classes.
Definition: vpException.h:73
int addPoint(double X, double Y, double Z, vpImagePoint &ip)
Tools for perspective camera calibration.
Definition: vpCalibration.h:71
XML parser to load and save intrinsic camera parameters.
static const vpColor green
Definition: vpColor.h:166
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:2233
static const vpColor red
Definition: vpColor.h:163
Class that defines what is a point.
Definition: vpPoint.h:59
static void setLambda(const double &lambda)
set the gain for the virtual visual servoing algorithm
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
void open(vpImage< vpRGBa > &I)
int save(const vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const unsigned int image_width=0, const unsigned int image_height=0)
int clearPoint()
Suppress all the point in the array of point.
static void display(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:206
The vpDisplayOpenCV allows to display image using the opencv library.
virtual void displayCross(const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)=0
Generic class defining intrinsic camera parameters.
virtual void setTitle(const char *title)=0
The vpDisplayGTK allows to display image using the GTK+ library version 1.2.
Definition: vpDisplayGTK.h:141
void acquire(vpImage< vpRGBa > &I)
void setFileName(const char *filename)
double get_px() const
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
unsigned int getHeight() const
Definition: vpImage.h:152
virtual bool getClick(bool blocking=true)=0
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
static bool readConfigVar(const std::string &var, float &value)
Definition: vpIoTools.cpp:811
static int computeCalibrationMulti(vpCalibrationMethodType method, std::vector< vpCalibration > &table_cal, vpCameraParameters &cam, double &globalReprojectionError, bool verbose=false)
static bool loadConfigFile(const std::string &confFile)
Definition: vpIoTools.cpp:760
vpRowVector t() const