detect_calibration_pattern.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
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     // Do subpixel ONLY IF THE PATTERN IS A CHESSBOARD
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); //take the 3x1 rotation representation to a 3x3 rotation matrix.
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   // This assumes that cv::Mats are stored as doubles. Is there a way to check this?
00116   // Since it's templated...
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 }


turtlebot_arm_kinect_calibration
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Thu Jun 6 2019 20:54:25