$search
00001 /* 00002 * Calibrate (i.e. find intrinsic and extrinsic calibration parameters) cameras 00003 * using left-right sets of images 00004 * 00005 * Copyright (c) 2009 Radu Bogdan Rusu <rusu -=- cs.tum.edu> 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above copyright 00015 * notice, this list of conditions and the following disclaimer in the 00016 * documentation and/or other materials provided with the distribution. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 * POSSIBILITY OF SUCH DAMAGE. 00029 * 00030 * $Id: calibration_standalone.h 189 2009-09-19 11:59:29Z veedee $ 00031 */ 00032 #ifndef CALIBRATION_STANDALONE_H 00033 #define CALIBRATION_STANDALONE_H 00034 00035 #include <opencv/cv.h> 00036 #include <opencv/highgui.h> 00037 #include <boost/algorithm/string.hpp> 00038 00039 #include <stdio.h> 00040 #include <vector> 00041 #include <iostream> 00042 #include <string> 00043 00044 #define NR_SQUARE_X 4 00045 #define NR_SQUARE_Y 6 00046 #define SQ_SIZE 41 00047 00048 #define DEBUG_GUI 1 00049 #define DEBUG_CORNERS_GUI 1 00050 00052 // Parse for a specific given command line argument. 00053 // Returns: the value sent as an int. 00054 int 00055 ParseArgument (int argc, char** argv, const char* str, int &val) 00056 { 00057 for (int i = 1; i < argc; i++) 00058 { 00059 // Search for the string 00060 if ((strcmp (argv[i], str) == 0) && (++i < argc)) 00061 { 00062 val = atoi (argv[i]); 00063 return (i-1); 00064 } 00065 } 00066 return (-1); 00067 } 00068 00070 // Parse for a specific given command line argument. 00071 // Returns: the value sent as a double. 00072 int 00073 ParseArgument (int argc, char** argv, const char* str, double &val) 00074 { 00075 for (int i = 1; i < argc; i++) 00076 { 00077 // Search for the string 00078 if ((strcmp (argv[i], str) == 0) && (++i < argc)) 00079 { 00080 val = atof (argv[i]); 00081 return (i-1); 00082 } 00083 } 00084 return (-1); 00085 } 00086 00088 // Parse for specific given command line arguments (range values X-Y). 00089 // Returns: the values sent as ints. 00090 int 00091 ParseRangeArguments (int argc, char** argv, const char* str, int &s, int &e) 00092 { 00093 std::vector<std::string> values; 00094 for (int i = 1; i < argc; i++) 00095 { 00096 // Search for the string 00097 if ((strcmp (argv[i], str) == 0) && (++i < argc)) 00098 { 00099 // look for ',' as a separator 00100 boost::split (values, argv[i], boost::is_any_of (","), boost::token_compress_on); 00101 if (values.size () != 2) 00102 fprintf (stderr, "Number of values for %s different than 2!\n", str); 00103 s = atoi (values.at (0).c_str ()); 00104 e = atoi (values.at (1).c_str ()); 00105 return (i-1); 00106 } 00107 } 00108 return (-1); 00109 } 00110 00112 // Parse command line arguments for file names. 00113 // Returns: a vector with file names indices. 00114 std::vector<int> 00115 ParseFileExtensionArgument (int argc, char** argv, const char *extension) 00116 { 00117 std::vector<int> indices; 00118 for (int i = 1; i < argc; i++) 00119 { 00120 std::string fname = std::string (argv[i]); 00121 std::string ext = std::string (extension); 00122 00123 // Needs to be at least 4: .ext 00124 if (fname.size () <= 4) 00125 continue; 00126 00127 // For being case insensitive 00128 std::transform (fname.begin (), fname.end (), fname.begin (), tolower); 00129 std::transform (ext.begin (), ext.end (), ext.begin (), tolower); 00130 00131 // Check if found 00132 std::string::size_type it; 00133 if ((it = fname.find (ext)) != std::string::npos) 00134 { 00135 // Additional check: we want to be able to differentiate between .p and .png 00136 if ((ext.size () - (fname.size () - it)) == 0) 00137 indices.push_back (i); 00138 } 00139 } 00140 return indices; 00141 } 00142 00144 // Display a cvMat on screen 00145 void 00146 printMatrix (CvMat *matrix, double value = 1.0) 00147 { 00148 for (int i = 0; i < matrix->height; i++) 00149 { 00150 for (int j = 0; j < matrix->width; j++) 00151 fprintf (stderr, " << %10.4f ", cvmGet (matrix, i, j) / value); 00152 fprintf (stderr, "\n"); 00153 } 00154 } 00155 00157 // Display a cvMat on screen 00158 void 00159 printTransformation (CvMat *rot, CvMat *tr) 00160 { 00161 for (int i = 0; i < rot->height; i++) 00162 { 00163 for (int j = 0; j < rot->width; j++) 00164 fprintf (stderr, " << %6.4f ", cvmGet (rot, i, j)); 00165 00166 fprintf (stderr, " << %6.4f \n", cvmGet (tr, i, 0)); 00167 } 00168 fprintf (stderr, " << 0 << 0 << 0 << 1\n"); 00169 } 00170 00175 std::vector <CvPoint3D64f> 00176 getObjectPoints (CvSize checkboard, double sq_size, int n_frames) 00177 { 00178 std::vector <CvPoint3D64f> points (checkboard.height * checkboard.width * n_frames); 00179 00180 for (int i = 0; i < checkboard.height; ++i) 00181 { 00182 for (int j = 0; j < checkboard.width; ++j) 00183 { 00184 points[i * checkboard.width + j] = cvPoint3D64f (sq_size * i, sq_size * j, 0); 00185 } 00186 } 00187 00188 int cs = checkboard.height * checkboard.width; 00189 for (int i = 1; i < n_frames; i++) 00190 copy (points.begin (), points.begin () + cs, points.begin () + i * cs); 00191 return points; 00192 } 00193 00194 00195 00197 // Define a sensor data struc to hold all data for a given <sensor>-<camera> entry 00198 struct SensorDataEntry 00199 { 00200 // All image data for a specified <sensor>-<camera> entry is stored here 00201 std::vector <IplImage*> images; 00202 00203 // Bookkeeping the pair numbers and the file paths 00204 std::vector <int> pairs; 00205 std::vector <std::string> paths; 00206 00207 // String identifiers for the sensor (sr4k, stoc, etc) and camera (left, right, intensity) images used 00208 std::string sensor; 00209 std::string camera; 00210 00211 // OpenCV matrices holding the internal parameters and related stuff 00212 CvMat *objectPoints; // The joint matrix of object points, 3xN or Nx3, where N is the total number of points in all views 00213 CvMat *imagePoints; // The joint matrix of corresponding image points, 2xN or Nx2, where N is the total number of points in all views 00214 CvMat *pointNumbers; // Vector containing numbers of points in each particular view, 1xM or Mx1, where M is the number of a scene views 00215 CvMat *intrinsic; // [fx 0 cx; 0 fy cy; 0 0 1] 00216 CvMat *distortion; // [k1, k2, p1, p2] 00217 00218 // Store estimated translations and rotations with respect to a world coordinate framework for a given image 00219 CvMat *translation; // optimized translation 00220 CvMat *rotation; // optimized rotation 00221 CvMat *translations; 00222 CvMat *rotations; // compact representation of rotation matrices (use cvRodrigues2) 00223 00224 // Comparator functions for std::find 00225 bool 00226 operator < (SensorDataEntry const & b) const 00227 { 00228 bool c = this->sensor < b.sensor; 00229 if (!c) 00230 return false; 00231 return this->camera < b.camera; 00232 } 00233 00234 bool 00235 operator > (SensorDataEntry const & b) const 00236 { 00237 bool c = this->sensor > b.sensor; 00238 if (!c) 00239 return false; 00240 return this->camera > b.camera; 00241 } 00242 00243 bool 00244 operator == (SensorDataEntry const & b) const 00245 { 00246 bool c = this->sensor == b.sensor; 00247 if (!c) 00248 return false; 00249 return this->camera == b.camera; 00250 } 00251 }; 00252 00254 // Release all allocated memory and prepare to exit 00255 void 00256 finishUp (std::vector<SensorDataEntry> inputData) 00257 { 00259 for (unsigned int i = 0; i < inputData.size (); i++) 00260 { 00261 SensorDataEntry s = inputData.at (i); 00262 for (unsigned int j = 0; j < s.pairs.size (); j++) 00263 cvReleaseImage (&s.images.at (j)); 00264 cvmFree (s.objectPoints); 00265 cvmFree (s.imagePoints); 00266 cvmFree (s.pointNumbers); 00267 cvmFree (s.intrinsic); 00268 cvmFree (s.distortion); 00269 cvmFree (s.translations); 00270 cvmFree (s.rotations); 00271 } 00272 cvDestroyAllWindows (); 00273 } 00274 00276 // Create and initialize all data structures from a set of given PNG file names 00277 std::vector<SensorDataEntry> 00278 createSensorEntries (int argc, char** argv, std::vector<int> pPNGFileIndices, CvSize checkboard, int ith) 00279 { 00280 std::vector<SensorDataEntry> inputData; 00281 std::vector<std::string> st1, st2, st3; 00282 00283 // ---[ Phase 1 : create NR-SID-CID entries 00284 for (unsigned int i = 0; i < pPNGFileIndices.size (); i++) 00285 { 00286 SensorDataEntry s; 00287 // Get the current entry 00288 std::string entry (argv[pPNGFileIndices.at (i)]); 00289 00290 // Parse and get the filename out 00291 boost::split (st1, entry, boost::is_any_of ("/"), boost::token_compress_on); 00292 std::string file = st1.at (st1.size () - 1); 00293 00294 // Parse inside the filename for NR-SID-CID 00295 boost::split (st2, file, boost::is_any_of ("."), boost::token_compress_on); 00296 boost::split (st3, st2.at (0), boost::is_any_of ("-"), boost::token_compress_on); 00297 int nr = atoi (st3.at (0).c_str ()); 00298 std::string sid = st3.at (1); 00299 std::string cid = st3.at (2); 00300 // Add <sensor>-<camera> entries 00301 s.sensor = sid; 00302 s.camera = cid; 00303 00304 // Check to see if we already have an entry with <sensor>-<camera> 00305 std::vector<SensorDataEntry>::iterator it = find (inputData.begin (), inputData.end (), s); 00306 // If we do, add the current image pair number to it 00307 if (it != inputData.end ()) 00308 { 00309 SensorDataEntry *pen = &(*it); 00310 pen->pairs.push_back (nr); 00311 pen->paths.push_back (entry); 00312 } 00313 // Else, create a new entry in inputData 00314 else 00315 { 00316 s.pairs.push_back (nr); 00317 s.paths.push_back (entry); 00318 inputData.push_back (s); 00319 } 00320 } 00321 00322 // ---[ Phase 2 : load image data into IplImage structures 00323 for (unsigned int i = 0; i < inputData.size (); i++) 00324 { 00325 SensorDataEntry s = inputData.at (i); 00326 fprintf (stderr, "Processing data for "); fprintf (stderr, "%s - %s", s.sensor.c_str (), s.camera.c_str ()); 00327 fprintf (stderr, " : "); 00328 00329 unsigned int nr_pairs = 0; 00330 std::vector <int> new_pairs; 00331 std::vector <std::string> new_paths; 00332 for (unsigned int j = 0; j < s.pairs.size (); j+=ith) 00333 { 00334 fprintf (stderr, "%d ", s.pairs.at (j)); 00335 new_pairs.push_back (s.pairs.at (j)); 00336 new_paths.push_back (s.paths.at (j)); 00337 // Load data into IplImage 00338 inputData.at (i).images.push_back ( cvLoadImage ( s.paths.at (j).c_str () ) ); 00339 nr_pairs++; 00340 } 00341 fprintf (stderr, " (%d x %d)\n", inputData.at (i).images.at (0)->width, inputData.at (i).images.at (0)->height); 00342 00343 inputData.at (i).pairs = new_pairs; 00344 inputData.at (i).paths = new_paths; 00345 00346 inputData.at (i).rotation = cvCreateMat (1, 3, CV_64FC1); 00347 inputData.at (i).translation = cvCreateMat (1, 3, CV_64FC1); 00348 // Initialize OpenCV related stuff 00349 inputData.at (i).intrinsic = cvCreateMat (3, 3, CV_64FC1); 00350 inputData.at (i).distortion = cvCreateMat (1, 4, CV_64FC1); 00351 // Allocate a 1D array (1 x MaxPairs) which stores the point indices 00354 // Allocate a 3D array (M x 3) for <x,y,z> comprised of M=Cw*Ch*MaxPairs values (alloc more than needed) 00357 // Allocate a 2D array (M x 2) for <u,v> comprised of M=Cw*Ch*MaxPairs values (alloc more than needed) 00360 } 00361 00362 // ---[ Phase 3 : check whether the number of pairs is the same across all <sensor>s-<camera>s 00363 unsigned int nr_pairs = inputData.at (0).pairs.size (); 00364 for (unsigned int i = 1; i < inputData.size (); i++) 00365 { 00366 SensorDataEntry s = inputData.at (i); 00367 if (s.pairs.size () != nr_pairs) 00368 fprintf (stderr, "Number of pairs for %s-%s (%d) differs than the standard %d!\n", s.sensor.c_str (), s.camera.c_str (), (int)s.pairs.size (), nr_pairs); 00369 } 00370 00371 return inputData; 00372 } 00373 00375 // Given a sensor entry and a number of images, detect and store the imagePoints 00376 // as the calibration checkboard corners 00377 // - also update {good,bad}Pairs, by keeping a list of pairs which are good/bad 00379 void 00380 getCalibrationCheckboardCorners (SensorDataEntry &sde, CvSize checkboard, double sq_size, 00381 std::vector<int> &badPairs, std::vector<int> &goodPairs) 00382 { 00383 CvPoint2D32f *corners = new CvPoint2D32f[checkboard.width * checkboard.height]; // allocate space for all corners 00384 std::vector<CvPoint2D32f> imagePoints_temp (checkboard.width * checkboard.height * sde.pairs.size ()); // allocate space for all possible 2D points 00385 00386 int validPtIdx = 0; // global point index 00387 00388 // Iterate over each image 00389 for (unsigned int i = 0; i < sde.pairs.size (); i++) 00390 { 00391 std::vector<int>::iterator bad_it = find (badPairs.begin (), badPairs.end (), sde.pairs.at (i)); 00392 if (bad_it != badPairs.end ()) 00393 { 00394 fprintf (stderr, "Pair number %d already marked as invalid. Continuing...\n", sde.pairs.at (i)); 00395 continue; 00396 } 00397 00398 // Convert each image to grayscale (BGR2GRAY, 1 channel) 00399 IplImage *grayImage = cvCreateImage (cvGetSize (sde.images.at (i)), IPL_DEPTH_8U, 1); 00400 cvCvtColor (sde.images.at (i), grayImage, CV_BGR2GRAY); 00401 00402 int cornerCount = 0; 00403 // Finds positions of internal corners of the chessboard in the newly created grayscale image 00404 if (cvFindChessboardCorners (grayImage, checkboard, corners, &cornerCount, CV_CALIB_CB_ADAPTIVE_THRESH))// | CV_CALIB_CB_NORMALIZE_IMAGE)) // | CV_CALIB_CB_FILTER_QUADS)) 00405 { 00406 fprintf (stderr, "["); fprintf (stderr, "%2d", sde.pairs.at (i)); fprintf (stderr, "/"); fprintf (stderr, "%2d", cornerCount); fprintf (stderr, "] "); 00407 // Refine the corner locations found using cvFindChessboardCorners 00408 cvFindCornerSubPix (grayImage, corners, cornerCount, 00409 //cvSize (11, 11), 00410 cvSize (5, 5), 00411 //checkboard, 00412 cvSize (-1, -1), 00413 cvTermCriteria (CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 10, 0.001)); 00414 00415 #if DEBUG_CORNERS_GUI 00416 char windowTitle[80]; 00417 sprintf (windowTitle, "%s-%s : %d", sde.sensor.c_str (), sde.camera.c_str (), sde.pairs.at (i)); 00418 // Create window 00419 cvNamedWindow (windowTitle, CV_WINDOW_AUTOSIZE); 00420 cvDrawChessboardCorners (grayImage, checkboard, corners, cornerCount, 1); 00421 #endif 00422 00423 // For each corner found in the image, increment the number of corners found for all images and store them in the image/object points 00424 for (int j = 0; j < cornerCount; j++, validPtIdx++) 00425 { 00426 if ( (sde.sensor == "sr4k") || (sde.sensor == "sr3k") || (sde.sensor == "thermal") ) 00427 { 00428 corners[j].x /= 2.0; corners[j].y /= 2.0; 00429 } 00430 imagePoints_temp[validPtIdx] = cvPoint2D32f (corners[j].x, corners[j].y); // Set the image points <u, v> as the freshly detected corners 00431 00432 #if DEBUG_CORNERS_GUI 00433 if (j == 0) cvCircle (sde.images.at (i), cvPoint ((int) corners[j].x, (int) corners[j].y), 2, CV_RGB (0, 255, 0), 1); // Mark the first circle with green 00434 else cvCircle (sde.images.at (i), cvPoint ((int) corners[j].x, (int) corners[j].y), 2, CV_RGB (0, 0, 255), 1); // And the rest with red 00435 #endif 00436 } // for 00437 #if DEBUG_CORNERS_GUI 00438 cvShowImage (windowTitle, grayImage); 00439 //cvWaitKey (0); // Wait until key pressed 00440 cvDestroyWindow (windowTitle); // Destroy previous window 00441 #endif 00442 goodPairs.push_back (i); // push <i> 00443 } // if (checkboardFound) 00444 else 00445 { 00446 if (cornerCount == checkboard.width * checkboard.height) 00447 { fprintf (stderr, "["); fprintf (stderr, "%2d", sde.pairs.at (i)); fprintf (stderr, "/"); fprintf (stderr, "0"); fprintf (stderr, "] "); } 00448 else 00449 { fprintf (stderr, "["); fprintf (stderr, "%2d", sde.pairs.at (i)); fprintf (stderr, "/"); fprintf (stderr, "%2d", cornerCount); fprintf (stderr, "] "); } 00450 badPairs.push_back (sde.pairs.at (i)); // push <i=421> and not <i> 00451 } 00452 00453 cvReleaseImage (&grayImage); 00454 } 00455 fprintf (stderr, "\n"); 00456 #if DEBUG 00457 fprintf (stderr, "Done: "); fprintf (stderr, "%d", (int)goodPairs.size ()); fprintf (stderr, " images.\n\n"); 00458 #endif 00459 00461 std::vector<CvPoint3D64f> vObjectPoints = getObjectPoints (checkboard, sq_size, goodPairs.size ()); 00462 00463 sde.objectPoints = cvCreateMat (checkboard.width * checkboard.height * goodPairs.size (), 3, CV_64FC1); 00464 sde.imagePoints = cvCreateMat (checkboard.width * checkboard.height * goodPairs.size (), 2, CV_64FC1); 00465 sde.pointNumbers = cvCreateMat (1, goodPairs.size (), CV_32SC1); 00466 00467 for (unsigned int i = 0; i < goodPairs.size (); i++) 00468 cvSet2D (sde.pointNumbers, 0, i, cvScalar (checkboard.width * checkboard.height)); 00469 00470 for (unsigned int i = 0; i < checkboard.width * checkboard.height * goodPairs.size (); i++) 00471 { 00472 // Set the 3D points <x, y, z = 0> by copying them from our generated checkboard pattern 00473 cvmSet (sde.objectPoints, i, 0, vObjectPoints[i].x); 00474 cvmSet (sde.objectPoints, i, 1, vObjectPoints[i].y); 00475 cvmSet (sde.objectPoints, i, 2, 0.0); 00476 00477 cvmSet (sde.imagePoints, i, 0, imagePoints_temp[i].x); 00478 cvmSet (sde.imagePoints, i, 1, imagePoints_temp[i].y); 00479 } 00480 00481 // Dealloc 00482 delete [] corners; 00483 } 00484 00486 // Creates a 4x4 transformation from a 1x3 R and a 1x3 t 00487 void 00488 get4x4TransformationMatrix (CvMat *R, CvMat *t, CvMat *T) 00489 { 00490 cvSetZero (T); 00491 CvMat *rot3x3 = cvCreateMat (3, 3, CV_64FC1); 00492 if (R->width == 3 && R->height == 3) 00493 rot3x3 = R; 00494 else 00495 cvRodrigues2 (R, rot3x3); 00496 00497 for (int i = 0; i < 3; i++) 00498 for (int j = 0; j < 3; j++) 00499 cvmSet (T, i, j, cvmGet (rot3x3, i, j)); 00500 00501 for (int j = 0; j < 3; j++) 00502 cvmSet (T, j, 3, cvmGet (t, 0, j)); 00503 00504 cvmSet (T, 3, 3, 1); 00505 if (R->width != 3 || R->height != 3) 00506 cvmFree (rot3x3); 00507 } 00508 00510 int 00511 getExtrinsicBetween (std::string left, std::string right, CvSize checkboard, 00512 std::vector<SensorDataEntry> inputData, int nr_pairs, int *nums) 00513 { 00514 SensorDataEntry sl, sr; 00515 std::vector<std::string> st; 00516 00517 boost::split (st, left, boost::is_any_of ("-"), boost::token_compress_on); 00518 00519 if (st.size () == 2) 00520 { 00521 sl.sensor = st.at (0); 00522 sl.camera = st.at (1); 00523 } 00524 else 00525 sl.sensor = st.at (0); 00526 std::vector<SensorDataEntry>::iterator left_it = find (inputData.begin (), inputData.end (), sl); 00527 if (left_it == inputData.end ()) 00528 { 00529 fprintf (stderr, "%s-%s not found!\n", sl.sensor.c_str (), sl.camera.c_str ()); 00530 return (-1); 00531 } 00532 00533 boost::split (st, right, boost::is_any_of ("-"), boost::token_compress_on); 00534 if (st.size () == 2) 00535 { 00536 sr.sensor = st.at (0); 00537 sr.camera = st.at (1); 00538 } 00539 else 00540 sr.sensor = st.at (0); 00541 std::vector<SensorDataEntry>::iterator right_it = find (inputData.begin (), inputData.end (), sr); 00542 if (right_it == inputData.end ()) 00543 { 00544 fprintf (stderr, "%s-%s not found!\n", sr.sensor.c_str (), sr.camera.c_str ()); 00545 return (-1); 00546 } 00547 00548 SensorDataEntry *pleft = &(*left_it); 00549 SensorDataEntry *pright = &(*right_it); 00550 00551 double R[3][3], T[3], E[3][3], F[3][3]; 00552 CvMat LR_Rot = cvMat (3, 3, CV_64F, R); 00553 CvMat LR_T = cvMat (3, 1, CV_64F, T); 00554 CvMat LR_E = cvMat (3, 3, CV_64F, E); 00555 CvMat LR_F = cvMat (3, 3, CV_64F, F); 00556 00557 cvStereoCalibrate (pleft->objectPoints, pleft->imagePoints, pright->imagePoints, 00558 pleft->pointNumbers, 00559 pleft->intrinsic, pleft->distortion, pright->intrinsic, pright->distortion, 00560 cvGetSize(inputData.at (0).images.at (0)), 00561 &LR_Rot, &LR_T, &LR_E, &LR_F, 00562 00563 cvTermCriteria (CV_TERMCRIT_ITER + CV_TERMCRIT_EPS, 100, 1e-5), 00564 CV_CALIB_USE_INTRINSIC_GUESS + 00565 CV_CALIB_FIX_ASPECT_RATIO + 00566 CV_CALIB_ZERO_TANGENT_DIST + 00567 CV_CALIB_SAME_FOCAL_LENGTH); 00568 00570 fprintf (stderr, " Transformation Matrix "); fprintf (stderr, "%s", left.c_str ()); fprintf (stderr, " -> " ); fprintf (stderr, "%s \n", right.c_str ()); 00571 printTransformation (&LR_Rot, &LR_T); 00572 00573 return (0); 00574 } 00575 00576 00579 void 00580 calculateIntrinsicParametersError (SensorDataEntry sde, 00581 std::vector<int> &badPairs, std::vector<int> goodPairs, 00582 double max_err) 00583 { 00584 // Calculate the back-projection error: residual 00585 double err = 0.0; 00586 CvMat *tmpObjPt = cvCreateMatHeader (2, 2, CV_64FC1); 00587 CvMat *tmpImgPt = cvCreateMatHeader (2, 2, CV_64FC1); 00588 00589 CvMat *tmpRotation = cvCreateMatHeader (1, 3, CV_64FC1); 00590 CvMat *tmpTranslation = cvCreateMatHeader (1, 3, CV_64FC1); 00591 00592 CvMat *bestRotation = NULL, *bestTranslation = NULL; 00593 double bestErr = FLT_MAX; 00594 int bestPair = 0; 00595 00596 // For each valid image pair 00597 int totalPtIdx = 0; 00598 fprintf (stderr, "Computing back-projection error for pair "); 00599 for (unsigned int i = 0; i < goodPairs.size (); i++) 00600 { 00601 fprintf (stderr, "%d", goodPairs.at (i)); 00602 unsigned int nrPts = sde.pointNumbers->data.i[i]; // this is always going to be equal with cornerCount, see line 995 00603 00604 // Create a new matrix where the projected 2D <u,v> points will be held 00605 CvMat *projImgPoints = cvCreateMat (nrPts, 2, CV_64FC1); 00606 00607 // Get the first nrPts from pair <i>, 3D (resObjPoints) and 2D (resImgPoints) 00608 cvGetSubRect (sde.objectPoints, tmpObjPt, cvRect (0, totalPtIdx, 3, nrPts)); 00609 cvGetSubRect (sde.imagePoints, tmpImgPt, cvRect (0, totalPtIdx, 2, nrPts)); 00610 00611 // And get the appropriate rotation and translation values 00612 cvGetSubRect (sde.rotations, tmpRotation, cvRect (0, i, 3, 1)); 00613 cvGetSubRect (sde.translations, tmpTranslation, cvRect (0, i, 3, 1)); 00614 00615 // Use the rotation and translations to project the 3D points from tmpObjPt onto the image plane 00616 // using the camera intrinsic parameters (sde.intrinsic, sde.distortion) and the current extrinsic (R, t) pair 00618 cvProjectPoints2 (tmpObjPt, tmpRotation, tmpTranslation, sde.intrinsic, sde.distortion, projImgPoints); 00619 00620 #if DEBUG_GUI 00621 char windowTitle[80]; 00622 sprintf (windowTitle, "%s-%s : %d", sde.sensor.c_str (), sde.camera.c_str (), sde.pairs.at (goodPairs.at (i))); 00623 // Create window 00624 cvNamedWindow (windowTitle, 1); 00625 #endif 00626 for (unsigned int j = 0; j < nrPts; j++) 00627 { 00628 #if DEBUG_GUI 00629 // Mark the original <u,v> points with green, and the newly projected ones with red 00630 cvCircle (sde.images.at (goodPairs.at (i)), cvPoint ((int) cvmGet (tmpImgPt, j, 0), (int) cvmGet (tmpImgPt, j, 1)), 3, CV_RGB (0, 255, 0), 2); 00631 cvCircle (sde.images.at (goodPairs.at (i)), cvPoint ((int) cvmGet (projImgPoints, j, 0), (int) cvmGet (projImgPoints, j, 1)), 3, CV_RGB (255, 0, 0), 2); 00632 #endif 00633 err += sqrt ( 00634 (cvmGet (tmpImgPt, j, 0) - cvmGet (projImgPoints, j, 0)) * (cvmGet (tmpImgPt, j, 0) - cvmGet (projImgPoints, j, 0)) + 00635 (cvmGet (tmpImgPt, j, 1) - cvmGet (projImgPoints, j, 1)) * (cvmGet (tmpImgPt, j, 1) - cvmGet (projImgPoints, j, 1)) 00636 ); 00637 } 00638 err /= (double)nrPts; 00639 00640 if (err > max_err) 00641 { 00642 badPairs.push_back (sde.pairs.at (goodPairs.at (i))); 00643 fprintf (stderr, "ME"); 00644 } 00645 fprintf (stderr, "(%.4g) ", err); 00646 00647 if (err < bestErr) 00648 { 00649 bestPair = sde.pairs.at (goodPairs.at (i)); 00650 bestErr = err; 00651 bestRotation = tmpRotation; 00652 bestTranslation = tmpTranslation; 00653 } 00654 #if DEBUG_GUI 00655 cvShowImage (windowTitle, sde.images.at (goodPairs.at (i))); 00656 cvWaitKey (0); // Wait until key pressed 00657 cvDestroyWindow (windowTitle); // Destroy windows 00658 #endif 00659 totalPtIdx += nrPts; 00660 cvReleaseMat (&projImgPoints); 00661 } // for (validImgPairs) 00662 fprintf (stderr, "\n"); 00663 00664 fprintf (stderr, "Best error is: "); fprintf (stderr, "%g", bestErr); fprintf (stderr, " for pair "); fprintf (stderr, "%d", bestPair); fprintf (stderr, " with: \n"); 00665 fprintf (stderr, "bestRotation : "); printMatrix (bestRotation); 00666 fprintf (stderr, "bestTranslation: "); printMatrix (bestTranslation, 1000.0); 00667 } 00668 00671 int 00672 computeIntrinsicParameters (SensorDataEntry &sde, CvSize checkboard, double sq_size, 00673 std::vector<int> &badPairs, 00674 double max_err, int wait) 00675 { 00676 fprintf (stderr, "\n"); 00677 fprintf (stderr, "Calibrating for "); fprintf (stderr, "%s-%s\n", sde.sensor.c_str (), sde.camera.c_str ()); 00678 00679 // Get the image size and double it 00680 CvSize imageSize = cvSize (sde.images.at (0)->width, sde.images.at (0)->height); 00681 00682 std::vector<int> goodPairs; 00683 getCalibrationCheckboardCorners (sde, checkboard, sq_size, badPairs, goodPairs); 00684 00685 if (goodPairs.size () == 0) 00686 return (-1); 00687 00688 // Calculate intrinsic camera parameters and estimate rotations and translations (extrinsic) 00689 sde.translations = cvCreateMat (goodPairs.size (), 3, CV_64FC1); 00690 sde.rotations = cvCreateMat (goodPairs.size (), 3, CV_64FC1); 00691 00692 // Finds intrinsic and extrinsic camera parameters using a calibration pattern 00695 fprintf (stderr, "Estimating intrinsic parameters for %s-%s...\n", sde.sensor.c_str (), sde.camera.c_str ()); 00696 cvCalibrateCamera2 (sde.objectPoints, sde.imagePoints, sde.pointNumbers, 00697 imageSize, sde.intrinsic, sde.distortion, sde.rotations, sde.translations, 00698 CV_CALIB_USE_INTRINSIC_GUESS);// | CV_CALIB_ZERO_TANGENT_DIST | CV_CALIB_FIX_K3 | CV_CALIB_FIX_K2); 00699 // Estimate the reprojection errors for each pair 00700 calculateIntrinsicParametersError (sde, badPairs, goodPairs, max_err); 00701 00702 return goodPairs.size (); 00703 } 00704 00707 void 00708 computeExtrinsicParameters (SensorDataEntry &sde, CvSize checkboard, int nr_pairs) 00709 { 00710 CvMat *tmpObjPt = cvCreateMatHeader (2, 2, CV_64FC1); 00711 CvMat *tmpImgPt = cvCreateMatHeader (2, 2, CV_64FC1); 00712 // Get the first nrPts from pair <i>, 3D (resObjPoints) and 2D (resImgPoints) 00713 cvGetSubRect (sde.objectPoints, tmpObjPt, cvRect (0, 0, 3, checkboard.width * checkboard.height)); 00714 cvGetSubRect (sde.imagePoints, tmpImgPt, cvRect (0, 0, 2, checkboard.width * checkboard.height)); 00715 00716 cvFindExtrinsicCameraParams2 (tmpObjPt, tmpImgPt, sde.intrinsic, sde.distortion, 00717 sde.rotation, sde.translation); 00718 fprintf (stderr, "bestRotation : "); printMatrix (sde.rotation); 00719 fprintf (stderr, "bestTranslation: "); printMatrix (sde.translation, 1000.0); 00720 00721 CvMat *T = cvCreateMat (4, 4, CV_64FC1); 00722 get4x4TransformationMatrix (sde.rotation, sde.translation, T); 00723 printMatrix (T); 00724 } 00725 00726 #endif