1 #include <opencv2/core/core.hpp>     2 #include <opencv2/imgproc/imgproc.hpp>     3 #include <opencv2/calib3d/calib3d.hpp>     4 #include <opencv2/highgui/highgui.hpp>    15 " \nexample command line for calibration from a live feed.\n"    16 "   calibration  -w 4 -h 5 -s 0.025 -o camera.yml -op -oe\n"    18 " example command line for calibration from a list of stored images:\n"    19 "   imagelist_creator image_list.xml *.png\n"    20 "   calibration -w 4 -h 5 -s 0.025 -o camera.yml -op -oe image_list.xml\n"    21 " where image_list.xml is the standard OpenCV XML/YAML\n"    22 " use imagelist_creator to create the xml or yaml list\n"    23 " file consisting of the list of strings, e.g.:\n"    25 "<?xml version=\"1.0\"?>\n"    30 "<!-- view002.png -->\n"    33 "one_extra_view.jpg\n"    35 "</opencv_storage>\n";
    41     "When the live video from camera is used as input, the following hot-keys may be used:\n"    42         "  <ESC>, 'q' - quit the program\n"    43         "  'g' - start capturing images\n"    44         "  'u' - switch undistortion on/off\n";
    48     printf( 
"This is a camera calibration sample.\n"    49         "Usage: calibration\n"    50         "     -w <board_width>         # the number of inner corners per one of board dimension\n"    51         "     -h <board_height>        # the number of inner corners per another board dimension\n"    52         "     [-pt <pattern>]          # the type of pattern: chessboard or circles' grid\n"    53         "     [-n <number_of_frames>]  # the number of frames to use for calibration\n"    54         "                              # (if not specified, it will be set to the number\n"    55         "                              #  of board views actually available)\n"    56         "     [-d <delay>]             # a minimum delay in ms between subsequent attempts to capture a next view\n"    57         "                              # (used only for video capturing)\n"    58         "     [-s <squareSize>]       # square size in some user-defined units (1 by default)\n"    59         "     [-o <out_camera_params>] # the output filename for intrinsic [and extrinsic] parameters\n"    60         "     [-op]                    # write detected feature points\n"    61         "     [-oe]                    # write extrinsic parameters\n"    62         "     [-zt]                    # assume zero tangential distortion\n"    63         "     [-a <aspectRatio>]      # fix aspect ratio (fx/fy)\n"    64         "     [-p]                     # fix the principal point at the center\n"    65         "     [-v]                     # flip the captured images around the horizontal axis\n"    66         "     [-V]                     # use a video file, and not an image list, uses\n"    67         "                              # [input_data] string for the video file name\n"    68         "     [-su]                    # show undistorted images after calibration\n"    69         "     [input_data]             # input data, one of the following:\n"    70         "                              #  - text file with a list of the images of the board\n"    71         "                              #    the text file can be generated with imagelist_creator\n"    72         "                              #  - name of video file with a video of the board\n"    73         "                              # if input_data not specified, a live view from the camera is used\n"    83         const vector<vector<Point3f> >& objectPoints,
    84         const vector<vector<Point2f> >& imagePoints,
    85         const vector<Mat>& rvecs, 
const vector<Mat>& tvecs,
    86         const Mat& cameraMatrix, 
const Mat& distCoeffs,
    87         vector<float>& perViewErrors )
    89     vector<Point2f> imagePoints2;
    90     int i, totalPoints = 0;
    91     double totalErr = 0, err;
    92     perViewErrors.resize(objectPoints.size());
    94     for( i = 0; i < (int)objectPoints.size(); i++ )
    96         projectPoints(Mat(objectPoints[i]), rvecs[i], tvecs[i],
    97                       cameraMatrix, distCoeffs, imagePoints2);
    98         err = norm(Mat(imagePoints[i]), Mat(imagePoints2), NORM_L2);
    99         int n = (int)objectPoints[i].size();
   100         perViewErrors[i] = (float)
std::sqrt(err*err/n);
   116         for( 
int i = 0; i < boardSize.height; i++ )
   117             for( 
int j = 0; j < boardSize.width; j++ )
   118                 corners.push_back(Point3f(
float(j*squareSize),
   119                                           float(i*squareSize), 0));
   123         for( 
int i = 0; i < boardSize.height; i++ )
   124             for( 
int j = 0; j < boardSize.width; j++ )
   125                 corners.push_back(Point3f(
float((2*j + i % 2)*squareSize),
   126                                           float(i*squareSize), 0));
   130         std::cerr<<  
"Unknown pattern type\n";
   135                     Size imageSize, Size boardSize, 
Pattern patternType,
   136                     float squareSize, 
float aspectRatio,
   137                     int flags, Mat& cameraMatrix, Mat& distCoeffs,
   138                     vector<Mat>& rvecs, vector<Mat>& tvecs,
   139                     vector<float>& reprojErrs,
   142     cameraMatrix = Mat::eye(3, 3, CV_64F);
   143     if( flags & CALIB_FIX_ASPECT_RATIO )
   144         cameraMatrix.at<
double>(0,0) = aspectRatio;
   146     distCoeffs = Mat::zeros(8, 1, CV_64F);
   148     vector<vector<Point3f> > objectPoints(1);
   151     objectPoints.resize(imagePoints.size(),objectPoints[0]);
   153     double rms = calibrateCamera(objectPoints, imagePoints, imageSize, cameraMatrix,
   154                     distCoeffs, rvecs, tvecs, flags|CALIB_FIX_K4|CALIB_FIX_K5);
   156     printf(
"RMS error reported by calibrateCamera: %g\n", rms);
   158     bool ok = checkRange(cameraMatrix) && checkRange(distCoeffs);
   161                 rvecs, tvecs, cameraMatrix, distCoeffs, reprojErrs);
   168                        Size imageSize, Size boardSize,
   169                        float squareSize, 
float aspectRatio, 
int flags,
   170                        const Mat& cameraMatrix, 
const Mat& distCoeffs,
   171                        const vector<Mat>& rvecs, 
const vector<Mat>& tvecs,
   172                        const vector<float>& reprojErrs,
   173                        const vector<vector<Point2f> >& imagePoints,
   176     FileStorage fs( filename, FileStorage::WRITE );
   180     struct tm *t2 = localtime( &tt );
   182     strftime( buf, 
sizeof(buf)-1, 
"%c", t2 );
   184     fs << 
"calibration_time" << buf;
   186     if( !rvecs.empty() || !reprojErrs.empty() )
   187         fs << 
"nframes" << (
int)std::max(rvecs.size(), reprojErrs.size());
   188     fs << 
"image_width" << imageSize.width;
   189     fs << 
"image_height" << imageSize.height;
   190     fs << 
"board_width" << boardSize.width;
   191     fs << 
"board_height" << boardSize.height;
   192     fs << 
"square_size" << squareSize;
   194     if( flags & CALIB_FIX_ASPECT_RATIO )
   195         fs << 
"aspectRatio" << aspectRatio;
   199         sprintf( buf, 
"flags: %s%s%s%s",
   200             flags & CALIB_USE_INTRINSIC_GUESS ? 
"+use_intrinsic_guess" : 
"",
   201             flags & CALIB_FIX_ASPECT_RATIO ? 
"+fix_aspectRatio" : 
"",
   202             flags & CALIB_FIX_PRINCIPAL_POINT ? 
"+fix_principal_point" : 
"",
   203             flags & CALIB_ZERO_TANGENT_DIST ? 
"+zero_tangent_dist" : 
"" );
   207     fs << 
"flags" << flags;
   209     fs << 
"camera_matrix" << cameraMatrix;
   210     fs << 
"distortion_coefficients" << distCoeffs;
   212     fs << 
"avg_reprojection_error" << totalAvgErr;
   213     if( !reprojErrs.empty() )
   214         fs << 
"per_view_reprojection_errors" << Mat(reprojErrs);
   216     if( !rvecs.empty() && !tvecs.empty() )
   218         CV_Assert(rvecs[0].type() == tvecs[0].type());
   219         Mat bigmat((
int)rvecs.size(), 6, rvecs[0].type());
   220         for( 
int i = 0; i < (int)rvecs.size(); i++ )
   222             Mat r = bigmat(Range(i, i+1), Range(0,3));
   223             Mat t = bigmat(Range(i, i+1), Range(3,6));
   225             CV_Assert(rvecs[i].rows == 3 && rvecs[i].cols == 1);
   226             CV_Assert(tvecs[i].rows == 3 && tvecs[i].cols == 1);
   232         fs << 
"extrinsic_parameters" << bigmat;
   235     if( !imagePoints.empty() )
   237         Mat imagePtMat((
int)imagePoints.size(), (int)imagePoints[0].size(), CV_32FC2);
   238         for( 
int i = 0; i < (int)imagePoints.size(); i++ )
   240             Mat r = imagePtMat.row(i).reshape(2, imagePtMat.cols);
   241             Mat imgpti(imagePoints[i]);
   244         fs << 
"image_points" << imagePtMat;
   251     FileStorage fs(filename, FileStorage::READ);
   254     FileNode n = fs.getFirstTopLevelNode();
   255     if( n.type() != FileNode::SEQ )
   257     FileNodeIterator it = n.begin(), it_end = n.end();
   258     for( ; it != it_end; ++it )
   259         l.push_back((
string)*it);
   260     }
catch(std::exception &ex){
   261         cerr<<
"ex:"<<ex.what()<<endl;
   266 static bool readInputFile( 
const string& filename, vector<string>& l )
throw(std::exception)
   271     cout<<
"read txt file"<<endl;
   273     std::ifstream file(
filename.c_str());
   289                 const vector<vector<Point2f> >& imagePoints,
   290                 Size imageSize, Size boardSize, 
Pattern patternType, 
float squareSize,
   291                 float aspectRatio, 
int flags, Mat& cameraMatrix,
   292                 Mat& distCoeffs, 
bool writeExtrinsics, 
bool writePoints )
   294     vector<Mat> rvecs, tvecs;
   295     vector<float> reprojErrs;
   296     double totalAvgErr = 0;
   298     bool ok = 
runCalibration(imagePoints, imageSize, boardSize, patternType, squareSize,
   299                    aspectRatio, flags, cameraMatrix, distCoeffs,
   300                    rvecs, tvecs, reprojErrs, totalAvgErr);
   301     printf(
"%s. avg reprojection error = %.2f\n",
   302            ok ? 
"Calibration succeeded" : 
"Calibration failed",
   307                          boardSize, squareSize, aspectRatio,
   308                          flags, cameraMatrix, distCoeffs,
   309                          writeExtrinsics ? rvecs : vector<Mat>(),
   310                          writeExtrinsics ? tvecs : vector<Mat>(),
   311                          writeExtrinsics ? reprojErrs : vector<float>(),
   312                          writePoints ? imagePoints : vector<vector<Point2f> >(),
   318 int main( 
int argc, 
char** argv )
   320     Size boardSize, imageSize;
   321     float squareSize = 1.f, aspectRatio = 1.f;
   322     Mat cameraMatrix, distCoeffs;
   323     const char* outputFilename = 
"out_camera_data.yml";
   324     const char* inputFilename = 0;
   327     bool writeExtrinsics = 
false, writePoints = 
false;
   328     bool undistortImage = 
false;
   330     cv::VideoCapture capture;
   331     bool flipVertical = 
false;
   332     bool showUndistorted = 
false;
   333     bool videofile = 
false;
   335     clock_t prevTimestamp = 0;
   338     vector<vector<Point2f> > imagePoints;
   339     vector<string> imageList;
   348     for( i = 1; i < argc; i++ )
   350         const char* 
s = argv[i];
   351         if( strcmp( s, 
"-w" ) == 0 )
   353             if( sscanf( argv[++i], 
"%u", &boardSize.width ) != 1 || boardSize.width <= 0 )
   354                 return fprintf( stderr, 
"Invalid board width\n" ), -1;
   356         else if( strcmp( s, 
"-h" ) == 0 )
   358             if( sscanf( argv[++i], 
"%u", &boardSize.height ) != 1 || boardSize.height <= 0 )
   359                 return fprintf( stderr, 
"Invalid board height\n" ), -1;
   361         else if( strcmp( s, 
"-pt" ) == 0 )
   364             if( !strcmp( argv[i], 
"circles" ) )
   366             else if( !strcmp( argv[i], 
"acircles" ) )
   368             else if( !strcmp( argv[i], 
"chessboard" ) )
   371                 return fprintf( stderr, 
"Invalid pattern type: must be chessboard or circles\n" ), -1;
   373         else if( strcmp( s, 
"-s" ) == 0 )
   375             if( sscanf( argv[++i], 
"%f", &squareSize ) != 1 || squareSize <= 0 )
   376                 return fprintf( stderr, 
"Invalid board square width\n" ), -1;
   378         else if( strcmp( s, 
"-n" ) == 0 )
   380             if( sscanf( argv[++i], 
"%u", &nframes ) != 1 || nframes <= 3 )
   381                 return printf(
"Invalid number of images\n" ), -1;
   383         else if( strcmp( s, 
"-a" ) == 0 )
   385             if( sscanf( argv[++i], 
"%f", &aspectRatio ) != 1 || aspectRatio <= 0 )
   386                 return printf(
"Invalid aspect ratio\n" ), -1;
   387             flags |= CALIB_FIX_ASPECT_RATIO;
   389         else if( strcmp( s, 
"-d" ) == 0 )
   391             if( sscanf( argv[++i], 
"%u", &delay ) != 1 || delay <= 0 )
   392                 return printf(
"Invalid delay\n" ), -1;
   394         else if( strcmp( s, 
"-op" ) == 0 )
   398         else if( strcmp( s, 
"-oe" ) == 0 )
   400             writeExtrinsics = 
true;
   402         else if( strcmp( s, 
"-zt" ) == 0 )
   404             flags |= CALIB_ZERO_TANGENT_DIST;
   406         else if( strcmp( s, 
"-p" ) == 0 )
   408             flags |= CALIB_FIX_PRINCIPAL_POINT;
   410         else if( strcmp( s, 
"-v" ) == 0 )
   414         else if( strcmp( s, 
"-V" ) == 0 )
   418         else if( strcmp( s, 
"-o" ) == 0 )
   420             outputFilename = argv[++i];
   422         else if( strcmp( s, 
"-su" ) == 0 )
   424             showUndistorted = 
true;
   426         else if( s[0] != 
'-' )
   429                 sscanf(s, 
"%d", &cameraId);
   434             return fprintf( stderr, 
"Unknown option %s", s ), -1;
   442             capture.open(inputFilename);
   445         capture.open(cameraId);
   447     if( !capture.isOpened() && imageList.empty() )
   448         return fprintf( stderr, 
"Could not initialize video (%d) capture\n",cameraId ), -2;
   450     if( !imageList.empty() )
   451         nframes = (
int)imageList.size();
   453     if( capture.isOpened() )
   456     namedWindow( 
"Image View", 1 );
   463         if( capture.isOpened() )
   469         else if( i < (
int)imageList.size() )
   470             view = imread(imageList[i], 1);
   474             if( imagePoints.size() > 0 )
   475                 runAndSave(outputFilename, imagePoints, imageSize,
   476                            boardSize, pattern, squareSize, aspectRatio,
   477                            flags, cameraMatrix, distCoeffs,
   478                            writeExtrinsics, writePoints);
   482         imageSize = view.size();
   485             flip( view, view, 0 );
   487         vector<Point2f> pointbuf;
   488         cvtColor(view, viewGray, COLOR_BGR2GRAY);
   494                 found = findChessboardCorners( view, boardSize, pointbuf,
   495                     CALIB_CB_ADAPTIVE_THRESH | CALIB_CB_FAST_CHECK | CALIB_CB_NORMALIZE_IMAGE);
   498                 found = findCirclesGrid( view, boardSize, pointbuf );
   501                 found = findCirclesGrid( view, boardSize, pointbuf, CALIB_CB_ASYMMETRIC_GRID );
   504                 return fprintf( stderr, 
"Unknown pattern type\n" ), -1;
   508         if( pattern == 
CHESSBOARD && found) cornerSubPix( viewGray, pointbuf, Size(11,11),
   509             Size(-1,-1), TermCriteria( TermCriteria::EPS+TermCriteria::COUNT, 30, 0.1 ));
   512            (!capture.isOpened() || clock() - prevTimestamp > delay*1e-3*CLOCKS_PER_SEC) )
   514             imagePoints.push_back(pointbuf);
   515             prevTimestamp = clock();
   516             blink = capture.isOpened();
   520             drawChessboardCorners( view, boardSize, Mat(pointbuf), found );
   522         string msg = mode == 
CAPTURING ? 
"100/100" :
   523             mode == 
CALIBRATED ? 
"Calibrated" : 
"Press 'g' to start";
   525         Size textSize = getTextSize(msg, 1, 1, 1, &baseLine);
   526         Point textOrigin(view.cols - 2*textSize.width - 10, view.rows - 2*baseLine - 10);
   531                 msg = format( 
"%d/%d Undist", (
int)imagePoints.size(), nframes );
   533                 msg = format( 
"%d/%d", (
int)imagePoints.size(), nframes );
   536         putText( view, msg, textOrigin, 1, 1,
   537                  mode != 
CALIBRATED ? Scalar(0,0,255) : Scalar(0,255,0));
   540             bitwise_not(view, view);
   544             Mat temp = view.clone();
   545             undistort(temp, view, cameraMatrix, distCoeffs);
   548         imshow(
"Image View", view);
   549         int key = 0xff & waitKey(capture.isOpened() ? 50 : 500);
   551         if( (key & 255) == 27 )
   555             undistortImage = !undistortImage;
   557         if( capture.isOpened() && key == 
'g' )
   563         if( mode == 
CAPTURING && imagePoints.size() >= (unsigned)nframes )
   565             if( 
runAndSave(outputFilename, imagePoints, imageSize,
   566                        boardSize, pattern, squareSize, aspectRatio,
   567                        flags, cameraMatrix, distCoeffs,
   568                        writeExtrinsics, writePoints))
   572             if( !capture.isOpened() )
   577     if( !capture.isOpened() && showUndistorted )
   579         Mat view, rview, map1, map2;
   580         initUndistortRectifyMap(cameraMatrix, distCoeffs, Mat(),
   581                                 getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, imageSize, 1, imageSize, 0),
   582                                 imageSize, CV_16SC2, map1, map2);
   584         for( i = 0; i < (int)imageList.size(); i++ )
   586             view = imread(imageList[i], 1);
   590             remap(view, rview, map1, map2, INTER_LINEAR);
   591             imshow(
"Image View", rview);
   592             int c = 0xff & waitKey();
   593             if( (c & 255) == 27 || c == 
'q' || c == 
'Q' )
 
static void saveCameraParams(const string &filename, Size imageSize, Size boardSize, float squareSize, float aspectRatio, int flags, const Mat &cameraMatrix, const Mat &distCoeffs, const vector< Mat > &rvecs, const vector< Mat > &tvecs, const vector< float > &reprojErrs, const vector< vector< Point2f > > &imagePoints, double totalAvgErr)
static bool runAndSave(const string &outputFilename, const vector< vector< Point2f > > &imagePoints, Size imageSize, Size boardSize, Pattern patternType, float squareSize, float aspectRatio, int flags, Mat &cameraMatrix, Mat &distCoeffs, bool writeExtrinsics, bool writePoints)
ROSCPP_DECL std::string remap(const std::string &name)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
int main(int argc, char **argv)
static bool runCalibration(vector< vector< Point2f > > imagePoints, Size imageSize, Size boardSize, Pattern patternType, float squareSize, float aspectRatio, int flags, Mat &cameraMatrix, Mat &distCoeffs, vector< Mat > &rvecs, vector< Mat > &tvecs, vector< float > &reprojErrs, double &totalAvgErr)
static bool readStringList(const string &filename, vector< string > &l)
static void calcChessboardCorners(Size boardSize, float squareSize, vector< Point3f > &corners, Pattern patternType=CHESSBOARD)
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const 
const char * liveCaptureHelp
static double computeReprojectionErrors(const vector< vector< Point3f > > &objectPoints, const vector< vector< Point2f > > &imagePoints, const vector< Mat > &rvecs, const vector< Mat > &tvecs, const Mat &cameraMatrix, const Mat &distCoeffs, vector< float > &perViewErrors)
static bool readInputFile(const string &filename, vector< string > &l)