00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <turtlebot_arm_kinect_calibration/detect_calibration_pattern.h>
00031
00032 void PatternDetector::setCameraMatrices(cv::Matx33d K_, cv::Mat D_)
00033 {
00034 K = K_;
00035 D = D_;
00036 }
00037
00038 void PatternDetector::setPattern(cv::Size grid_size_, float square_size_, Pattern pattern_type_, cv::Point3f offset_)
00039 {
00040 ideal_points = calcChessboardCorners(grid_size_, square_size_, pattern_type_, offset_);
00041 pattern_type = pattern_type_;
00042 grid_size = grid_size_;
00043 square_size = square_size_;
00044 }
00045
00046 object_pts_t PatternDetector::calcChessboardCorners(cv::Size boardSize, float squareSize, Pattern patternType,
00047 cv::Point3f offset)
00048 {
00049 object_pts_t corners;
00050 switch (patternType)
00051 {
00052 case CHESSBOARD:
00053 case CIRCLES_GRID:
00054 for (int i = 0; i < boardSize.height; i++)
00055 for (int j = 0; j < boardSize.width; j++)
00056 corners.push_back(cv::Point3f(float(j * squareSize), float(i * squareSize), 0) + offset);
00057 break;
00058 case ASYMMETRIC_CIRCLES_GRID:
00059 for (int i = 0; i < boardSize.height; i++)
00060 for (int j = 0; j < boardSize.width; j++)
00061 corners.push_back(cv::Point3f(float(i * squareSize), float((2 * j + i % 2) * squareSize), 0) + offset);
00062 break;
00063 default:
00064 std::logic_error("Unknown pattern type.");
00065 }
00066 return corners;
00067 }
00068
00069 int PatternDetector::detectPattern(cv::Mat& image_in, Eigen::Vector3f& translation, Eigen::Quaternionf& orientation,
00070 cv::Mat& image_out)
00071 {
00072 translation.setZero();
00073 orientation.setIdentity();
00074
00075 bool found = false;
00076
00077 observation_pts_t observation_points;
00078
00079 switch (pattern_type)
00080 {
00081 case ASYMMETRIC_CIRCLES_GRID:
00082 found = cv::findCirclesGrid(image_in, grid_size, observation_points,
00083 cv::CALIB_CB_ASYMMETRIC_GRID | cv::CALIB_CB_CLUSTERING);
00084 break;
00085 case CHESSBOARD:
00086 found = cv::findChessboardCorners(image_in, grid_size, observation_points, cv::CALIB_CB_ADAPTIVE_THRESH);
00087 break;
00088 case CIRCLES_GRID:
00089 found = cv::findCirclesGrid(image_in, grid_size, observation_points, cv::CALIB_CB_SYMMETRIC_GRID);
00090 break;
00091 }
00092
00093 if (found)
00094 {
00095
00096 if (pattern_type == CHESSBOARD)
00097 {
00098 cv::cornerSubPix(image_in, observation_points, cv::Size(5, 5), cv::Size(-1, -1),
00099 cv::TermCriteria(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 100, 0.01));
00100 }
00101
00102 cv::solvePnP(cv::Mat(ideal_points), cv::Mat(observation_points), K, D, rvec, tvec, false);
00103 cv::Rodrigues(rvec, R);
00104
00105 cv::drawChessboardCorners(image_out, grid_size, cv::Mat(observation_points), found);
00106
00107 convertCVtoEigen(tvec, R, translation, orientation);
00108 }
00109
00110 return found;
00111 }
00112
00113 void convertCVtoEigen(cv::Mat& tvec, cv::Mat& R, Eigen::Vector3f& translation, Eigen::Quaternionf& orientation)
00114 {
00115
00116
00117 translation = Eigen::Vector3f(tvec.at<double>(0, 0), tvec.at<double>(0, 1), tvec.at<double>(0, 2));
00118
00119 Eigen::Matrix3f Rmat;
00120 Rmat << R.at<double>(0, 0), R.at<double>(0, 1), R.at<double>(0, 2),
00121 R.at<double>(1, 0), R.at<double>(1, 1), R.at<double>(1, 2),
00122 R.at<double>(2, 0), R.at<double>(2, 1), R.at<double>(2, 2);
00123
00124 orientation = Eigen::Quaternionf(Rmat);
00125 }