40 #include <opencv2/imgproc/imgproc.hpp> 
   41 #include <opencv2/calib3d/calib3d.hpp> 
   54                              calibration_msgs::CalibrationPattern& result)
 
   70   const int scaled_width  = (int) (.5 + image.cols  * config_.width_scaling);
 
   71   const int scaled_height = (int) (.5 + image.rows * config_.height_scaling);
 
   73   cv::resize(image, image_scaled, cv::Size(scaled_width, scaled_height), 0, 0, cv::INTER_LINEAR);
 
   76   vector<cv::Point2f> cv_corners;
 
   77   cv_corners.resize(config_.num_x*config_.num_y);
 
   80   cv::Size board_size(config_.num_x, config_.num_y);
 
   81   int found = cv::findChessboardCorners( image_scaled, board_size, cv_corners, cv::CALIB_CB_ADAPTIVE_THRESH) ;
 
   89     cv::Size subpixel_window(config_.subpixel_window,
 
   90                                        config_.subpixel_window);
 
   91     cv::Size subpixel_zero_zone(config_.subpixel_zero_zone,
 
   92                                        config_.subpixel_zero_zone);
 
   95     cv::cornerSubPix( image_scaled, cv_corners, 
 
   98                        cv::TermCriteria(cv::TermCriteria::MAX_ITER,20,1e-2));
 
  104   result.header.stamp    = ros_image->header.stamp;
 
  105   result.header.frame_id = ros_image->header.frame_id;
 
  107   result.object_points.resize(config_.num_x * config_.num_y);
 
  108   for (
unsigned int i=0; i < config_.num_y; i++)
 
  110     for (
unsigned int j=0; j < config_.num_x; j++)
 
  112       result.object_points[i*config_.num_x + j].x = j*config_.spacing_x;
 
  113       result.object_points[i*config_.num_x + j].y = i*config_.spacing_y;
 
  114       result.object_points[i*config_.num_x + j].z = 0.0;
 
  118   result.image_points.resize(cv_corners.size());
 
  120   for (
size_t i=0; i < cv_corners.size(); i++)
 
  122     result.image_points[i].x = cv_corners[i].x / config_.width_scaling;
 
  123     result.image_points[i].y = cv_corners[i].y / config_.height_scaling;
 
  126   result.success = found;