30 #include <boost/thread/mutex.hpp> 
   33 #if ( CV_MAJOR_VERSION >= 4) 
   34 #include <opencv2/opencv.hpp> 
   35 #include <opencv2/highgui/highgui_c.h> 
   36 #include <opencv2/imgproc/types_c.h> 
   37 #include <opencv2/imgproc/imgproc_c.h> 
   38 #include <opencv2/calib3d/calib3d_c.h> 
   40 #define CV_RGB( r, g, b )  cvScalar( (b), (g), (r), 0 ) 
   41 #define CvPoint2D32f cv::Point2f 
   42 #define CvSize cv::Size 
   44 #include "opencv/cv.hpp" 
   45 #include "opencv/highgui.h" 
   48 #include "sensor_msgs/Image.h" 
   51 #include <sys/timeb.h>     
   58 T 
SQR(T t) { 
return t*t; }
 
   86   CheckerboardCalibration() : frame(NULL), _intrinsic_matrix(NULL), _distortion_coeffs(NULL), _pUndistortionMapX(NULL), _pUndistortionMapY(NULL), _bHasCalibration(false), _bClearData(false), _bTakeObservation(false)
 
   88         _nh.
param(
"display",display,1);
 
   94         if( !_nh.
getParam(
"grid_size_x",dimx) ) {
 
   98         if( !_nh.
getParam(
"grid_size_y",dimy) ) {
 
  102         if( !_nh.
getParam(
"rect_size_x",fRectSize[0]) ) {
 
  106         if( !_nh.
getParam(
"rect_size_y",fRectSize[1]) ) {
 
  111         _checkerboard.
griddims = cvSize(dimx,dimy);
 
  112         _checkerboard.
grid3d.resize(dimx*dimy);
 
  114         for(
int y=0; y<dimy; ++y)
 
  115             for(
int x=0; x<dimx; ++x)
 
  116                 _checkerboard.
grid3d[j++] = 
Vector(x*fRectSize[0], y*fRectSize[1], 0);
 
  118         if( _intrinsic_matrix == NULL )
 
  119             _intrinsic_matrix = cvCreateMat(3,3,CV_32FC1);
 
  120         if( _distortion_coeffs == NULL )
 
  121             _distortion_coeffs = cvCreateMat(4,1,CV_32FC1);
 
  124             cvNamedWindow(
"Checkerboard Detector", CV_WINDOW_AUTOSIZE);
 
  125             cvSetMouseCallback(
"Checkerboard Detector", MouseCallback, 
this);
 
  126             cvNamedWindow(
"Calibration Result", CV_WINDOW_AUTOSIZE);
 
  127             cvSetMouseCallback(
"Calibration Result", MouseCallback, 
this);
 
  128             cvStartWindowThread();
 
  137             cvReleaseImage(&frame);
 
  138         if( _intrinsic_matrix )
 
  139             cvReleaseMat(&_intrinsic_matrix);
 
  140         if( _distortion_coeffs )
 
  141             cvReleaseMat(&_distortion_coeffs);
 
  142         if( _pUndistortionMapX )
 
  143             cvReleaseImage(&_pUndistortionMapX);
 
  144         if( _pUndistortionMapY )
 
  145             cvReleaseImage(&_pUndistortionMapY);
 
  149     void image_cb2(
const sensor_msgs::ImageConstPtr& image_msg)
 
  153     void image_cb(
const sensor_msgs::ImageConstPtr& image_msg)
 
  162 #if ( CV_MAJOR_VERSION >= 4) 
  163         IplImage imggray = cvIplImage(_cvbridge->image);
 
  165         IplImage imggray = _cvbridge->image;
 
  167         IplImage *pimggray = &imggray;
 
  170             if( frame != NULL && (frame->width != (
int)pimggray->width || frame->height != (
int)pimggray->height) ) {
 
  171                 cvReleaseImage(&frame);
 
  175                 frame = cvCreateImage(cvSize(pimggray->width,pimggray->height),IPL_DEPTH_8U, 3);
 
  177             cvCvtColor(pimggray,frame,CV_GRAY2RGB);
 
  181         _checkerboard.
corners.resize(_checkerboard.
grid3d.size()+64);
 
  182 #if ( CV_MAJOR_VERSION >= 4) 
  183         int allfound = cv::findChessboardCorners( cv::cvarrToMat(pimggray), _checkerboard.
griddims, _checkerboard.
corners, CV_CALIB_CB_ADAPTIVE_THRESH );
 
  185         int allfound = cvFindChessboardCorners( pimggray, _checkerboard.
griddims, &_checkerboard.
corners[0],
 
  186                                                 &ncorners, CV_CALIB_CB_ADAPTIVE_THRESH );
 
  188         _checkerboard.
corners.resize(ncorners);        
 
  190         if(allfound && ncorners == (
int)_checkerboard.
grid3d.size()) {
 
  192 #if ( CV_MAJOR_VERSION >= 4) 
  193             cornerSubPix(cv::cvarrToMat(pimggray), _checkerboard.
corners, cvSize(5,5),cvSize(-1,-1),
 
  194                          cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
 
  196             cvFindCornerSubPix(pimggray, &_checkerboard.
corners[0], _checkerboard.
corners.size(), cvSize(5,5),cvSize(-1,-1),
 
  197                                cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
 
  201             _checkerboard.
corners.resize(0);
 
  204             ROS_INFO(
"clearing current calibration data");
 
  205             _vAllPoints.resize(0);
 
  206             _vNumPointsPerImage.resize(0);
 
  207             _bHasCalibration = 
false;
 
  211         if( _bTakeObservation ) {
 
  212             _bTakeObservation = 
false;
 
  214             if(allfound && ncorners == (
int)_checkerboard.
grid3d.size()) {
 
  216                 for(vector<CvPoint2D32f>::iterator it = _checkerboard.
corners.begin(); it != _checkerboard.
corners.end(); ++it)
 
  217                     _vAllPoints.push_back(*it);
 
  218                 _vNumPointsPerImage.push_back(_checkerboard.
corners.size());
 
  222                 CvMat object_points, image_points, point_counts;
 
  224                 vector<float> vobject_points;
 
  225                 vobject_points.reserve(_vNumPointsPerImage.size()*3*_checkerboard.
grid3d.size());
 
  226                 for(
size_t j = 0; j < _vNumPointsPerImage.size(); ++j) {
 
  227                     for(
size_t i = 0; i < _checkerboard.
grid3d.size(); ++i) {
 
  228                         vobject_points.push_back(_checkerboard.
grid3d[i].x);
 
  229                         vobject_points.push_back(_checkerboard.
grid3d[i].y);
 
  230                         vobject_points.push_back(_checkerboard.
grid3d[i].z);
 
  234                 cvInitMatHeader(&object_points, vobject_points.size()/3,3,CV_32FC1, &vobject_points[0]);
 
  235                 cvInitMatHeader(&image_points, _vAllPoints.size(), 2, CV_32FC1, &_vAllPoints[0]);
 
  236                 cvInitMatHeader(&point_counts, _vNumPointsPerImage.size(), 1, CV_32SC1, &_vNumPointsPerImage[0]);
 
  238                 CvMat* rotation_vectors = cvCreateMat(_vNumPointsPerImage.size(),3,CV_32FC1);
 
  239                 CvMat* translation_vectors = cvCreateMat(_vNumPointsPerImage.size(),3,CV_32FC1);
 
  241 #if ( CV_MAJOR_VERSION >= 4) 
  243                 std::vector<std::vector<cv::Point3f> > objectPoints;
 
  244                 std::vector<std::vector<cv::Point2f> > imagePoints;
 
  245                 std::vector<cv::Mat> rvecs;
 
  246                 std::vector<cv::Mat> tvecs;
 
  247                 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
 
  248                 cv::calibrateCamera(objectPoints, imagePoints,
 
  249                                     cv::Size(frame->width,frame->height),
 
  250                                     cv::cvarrToMat(_intrinsic_matrix),
 
  251                                     cv::cvarrToMat(_distortion_coeffs),
 
  253                                     stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors); 
 
  255                 cvCalibrateCamera2(&object_points, &image_points,
 
  256                                    &point_counts, cvSize(frame->width,frame->height),
 
  257                                    _intrinsic_matrix, _distortion_coeffs,
 
  258                                    rotation_vectors, translation_vectors, 0);
 
  263                 for(
size_t i = 0; i < _vNumPointsPerImage.size(); ++i) {
 
  264                     CvMat cur_object_points, rotation_vector, translation_vector;
 
  266                     cvInitMatHeader(&cur_object_points, _vNumPointsPerImage[i],3,CV_32FC1, &vobject_points[0]);
 
  267                     cvInitMatHeader(&rotation_vector, 3, 1, CV_32FC1, &rotation_vectors->data.fl[3*i]);
 
  268                     cvInitMatHeader(&translation_vector, 3, 1, CV_32FC1, &translation_vectors->data.fl[3*i]);
 
  269                     CvMat* new_image_points = cvCreateMat(_vNumPointsPerImage[i], 2, CV_32FC1);
 
  270 #if ( CV_MAJOR_VERSION >= 4) 
  271                     cv::projectPoints(cv::cvarrToMat(&cur_object_points),
 
  272                                       cv::cvarrToMat(&rotation_vector),
 
  273                                       cv::cvarrToMat(&translation_vector),
 
  274                                       cv::cvarrToMat(&_intrinsic_matrix),
 
  275                                       cv::cvarrToMat(&_distortion_coeffs),
 
  276                                       cv::cvarrToMat(&new_image_points));
 
  278                     cvProjectPoints2(&cur_object_points, &rotation_vector, &translation_vector, _intrinsic_matrix,
 
  279                                      _distortion_coeffs, new_image_points);
 
  282                     for(
int j = 0; j < _vNumPointsPerImage[i]; ++j)
 
  283                         err += 
SQR(new_image_points->data.fl[2*j]-_vAllPoints[off+j].x) + 
SQR(new_image_points->data.fl[2*j+1]-_vAllPoints[off+j].y);
 
  285                     cvReleaseMat(&new_image_points);
 
  286                     off += _vNumPointsPerImage[i];
 
  288                 err = sqrt(err/(
double)_vAllPoints.size());
 
  290                 ROS_INFO(
"calibration done, reprojection error = %f", (
float)err);
 
  292                 for(
int i = 0; i < 3; ++i) {
 
  293                     ROS_INFO(
"%15f %15f %15f", _intrinsic_matrix->data.fl[3*i], _intrinsic_matrix->data.fl[3*i+1], _intrinsic_matrix->data.fl[3*i+2]);
 
  294                     _tProjection.
m[4*i+0] = _intrinsic_matrix->data.fl[3*i+0];
 
  295                     _tProjection.
m[4*i+1] = _intrinsic_matrix->data.fl[3*i+1];
 
  296                     _tProjection.
m[4*i+2] = _intrinsic_matrix->data.fl[3*i+2];
 
  298                 ROS_INFO(
"distortion: %f %f %f %f", _distortion_coeffs->data.fl[0], _distortion_coeffs->data.fl[1], _distortion_coeffs->data.fl[2], _distortion_coeffs->data.fl[3]);
 
  300                 cvReleaseMat(&rotation_vectors);
 
  301                 cvReleaseMat(&translation_vectors);
 
  304                 if( _pUndistortionMapX == NULL )
 
  305                     _pUndistortionMapX = cvCreateImage( cvSize(frame->width, frame->height), IPL_DEPTH_32F, 1);
 
  306                 if( _pUndistortionMapY == NULL )
 
  307                     _pUndistortionMapY = cvCreateImage( cvSize(frame->width, frame->height), IPL_DEPTH_32F, 1);
 
  309 #if defined(HAVE_CV_UNDISTORT_RECTIFY_MAP) || ( CV_MAJOR_VERSION >= 4) // for newer opencv versions, *have* to use cvInitUndistortRectifyMap 
  310                 float feye[9] = {1,0,0,0,1,0,0,0,1};
 
  311                 CvMat eye = cvMat(3,3,CV_32FC1, feye);
 
  312 #if CV_MAJOR_VERSION >= 4 
  314                 cv::initUndistortRectifyMap(cv::cvarrToMat(&_intrinsic_matrix),cv::cvarrToMat(&_distortion_coeffs),cv::cvarrToMat(&eye),cv::cvarrToMat(&_intrinsic_matrix),size,CV_32FC1,cv::cvarrToMat(_pUndistortionMapX),cv::cvarrToMat(_pUndistortionMapY));
 
  316                 cvInitUndistortRectifyMap(_intrinsic_matrix,_distortion_coeffs,&eye,_intrinsic_matrix,_pUndistortionMapX, _pUndistortionMapY);
 
  319                 cvInitUndistortMap( _intrinsic_matrix, _distortion_coeffs, _pUndistortionMapX, _pUndistortionMapY );
 
  321                 _bHasCalibration = 
true;
 
  328             if( _bHasCalibration ) {
 
  329                 IplImage* frame_undist = cvCloneImage(frame);
 
  330                 IplImage* pimggray_undist = cvCloneImage(pimggray);
 
  332                 cvRemap( pimggray, pimggray_undist, _pUndistortionMapX, _pUndistortionMapY, CV_INTER_LINEAR + CV_WARP_FILL_OUTLIERS);
 
  333                 cvRemap( frame, frame_undist, _pUndistortionMapX, _pUndistortionMapY, CV_INTER_LINEAR + CV_WARP_FILL_OUTLIERS);
 
  336                 vector<CvPoint2D32f> corners(_checkerboard.
grid3d.size()+64);
 
  337 #if ( CV_MAJOR_VERSION >= 4) 
  338                 int allfound = cv::findChessboardCorners( cv::cvarrToMat(pimggray_undist),
 
  340                                                           CV_CALIB_CB_ADAPTIVE_THRESH );
 
  342                 int allfound = cvFindChessboardCorners( pimggray_undist, _checkerboard.
griddims, &corners[0],
 
  343                                                         &ncorners, CV_CALIB_CB_ADAPTIVE_THRESH );
 
  345                 corners.resize(ncorners);
 
  347                 if(allfound && ncorners == (
int)_checkerboard.
grid3d.size()) {
 
  349 #if ( CV_MAJOR_VERSION >= 4) 
  350                   cornerSubPix(cv::cvarrToMat(pimggray_undist), corners, cvSize(5,5),cvSize(-1,-1),
 
  351                                        cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
 
  353                     cvFindCornerSubPix(pimggray_undist, &corners[0], corners.size(), cvSize(5,5),cvSize(-1,-1),
 
  354                                        cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
 
  362                     int inds[4] = {0, 
s.width-1, 
s.width*(
s.height-1), 
s.width*
s.height-1 };
 
  364                     for(
int i = 0; i < 4; ++i) {
 
  365                         Vector p = _tProjection * tlocal * _checkerboard.
grid3d[inds[i]];
 
  366                         X[i].x = (int)(p.
x/p.
z);
 
  367                         X[i].y = (int)(p.
y/p.
z);
 
  371                     CvScalar col0 = CV_RGB(255,0,0);
 
  372                     CvScalar col1 = CV_RGB(0,255,0);
 
  373                     cvLine(frame_undist, X[0], X[1], col0, 1);
 
  374                     cvLine(frame_undist, X[0], X[2], col1, 1);
 
  377                     for(
size_t i = 0; i < _checkerboard.
grid3d.size(); ++i) {
 
  378                         Vector p = _tProjection * tlocal * _checkerboard.
grid3d[i];
 
  379                         int x = (int)(p.
x/p.
z);
 
  380                         int y = (int)(p.
y/p.
z);
 
  381                         cvCircle(frame_undist, cvPoint(x,y), 6, CV_RGB(0,0,0), 2);
 
  382                         cvCircle(frame_undist, cvPoint(x,y), 2, CV_RGB(0,0,0), 2);
 
  383                         cvCircle(frame_undist, cvPoint(x,y), 4, CV_RGB(128,128,0), 3);
 
  386                     cvCircle(frame_undist, X[0], 3, CV_RGB(255,255,128), 3);
 
  389                 cvShowImage(
"Calibration Result",frame_undist);
 
  390                 cvReleaseImage(&frame_undist);
 
  393             if(allfound && ncorners == (
int)_checkerboard.
grid3d.size())
 
  394 #if ( CV_MAJOR_VERSION >= 4) 
  395               cv::drawChessboardCorners(cv::cvarrToMat(frame), _checkerboard.
griddims, _checkerboard.
corners, 1);
 
  397                 cvDrawChessboardCorners(frame, _checkerboard.
griddims, &_checkerboard.
corners[0], _checkerboard.
corners.size(), 1);
 
  399             cvShowImage(
"Checkerboard Detector",frame);
 
  405         CvMat *objpoints = cvCreateMat(3,objpts.size(),CV_32FC1);
 
  406         for(
size_t i=0; i<objpts.size(); ++i) {
 
  407             cvSetReal2D(objpoints, 0,i, objpts[i].x);
 
  408             cvSetReal2D(objpoints, 1,i, objpts[i].y);
 
  409             cvSetReal2D(objpoints, 2,i, objpts[i].z);
 
  415         cvInitMatHeader(&R3, 3, 1, CV_32FC1, fR3);
 
  416         cvInitMatHeader(&T3, 3, 1, CV_32FC1, &pose.
trans.x);
 
  420         cvInitMatHeader(&kcmat,1,4,CV_32FC1,kc);
 
  423         cvInitMatHeader(&img_points, 1,imgpts.size(), CV_32FC2, 
const_cast<CvPoint2D32f*
>(&imgpts[0]));
 
  425 #if CV_MAJOR_VERSION >= 4 
  426         cv::solvePnP(cv::cvarrToMat(objpoints), cv::cvarrToMat(&img_points), cv::cvarrToMat(_intrinsic_matrix), cv::cvarrToMat(&kcmat), cv::cvarrToMat(&R3), cv::cvarrToMat(&T3), 
true, cv::SOLVEPNP_ITERATIVE);
 
  428         cvFindExtrinsicCameraParams2(objpoints, &img_points, _intrinsic_matrix, &kcmat, &R3, &T3);
 
  430         cvReleaseMat(&objpoints);
 
  432         double fang = sqrt(fR3[0]*fR3[0] + fR3[1]*fR3[1] + fR3[2]*fR3[2]);
 
  440             double fmult = sin(fang/2)/fang;
 
  441             pose.
rot.x = cos(fang/2);
 
  442             pose.
rot.y = fR3[0]*fmult;
 
  443             pose.
rot.z = fR3[1]*fmult;
 
  444             pose.
rot.w = fR3[2]*fmult;
 
  458         case CV_EVENT_RBUTTONDOWN:
 
  461         case CV_EVENT_MBUTTONDOWN:
 
  462             _bTakeObservation = 
true;
 
  468 int main(
int argc, 
char **argv)
 
  470     ros::init(argc,argv,
"checkerboard_calibration");