detect_calibration_pattern.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef _DETECT_CALIBRATION_PATTERN_
31 #define _DETECT_CALIBRATION_PATTERN_
32 
33 #include <opencv2/core/core.hpp>
34 #include <opencv2/calib3d/calib3d.hpp>
35 #include <opencv2/calib3d/calib3d.hpp>
36 #include <opencv2/highgui/highgui.hpp>
37 #include <opencv2/imgproc/imgproc.hpp>
38 
39 #include <Eigen/Dense>
40 #include <Eigen/Geometry>
41 #include <Eigen/StdVector>
42 
43 #include <iostream>
44 #include <stdexcept>
45 
46 using namespace std;
47 
48 enum Pattern
49 {
51 };
52 
53 typedef std::vector<cv::Point3f> object_pts_t;
54 typedef std::vector<cv::Point2f> observation_pts_t;
55 
56 void convertCVtoEigen(cv::Mat& tvec, cv::Mat& R, Eigen::Vector3f& translation, Eigen::Quaternionf& orientation);
57 
59 {
60 public:
62 
63  static object_pts_t calcChessboardCorners(cv::Size boardSize, float squareSize, Pattern patternType = CHESSBOARD,
64  cv::Point3f offset = cv::Point3f());
65 
66  int detectPattern(cv::Mat& image_in, Eigen::Vector3f& translation, Eigen::Quaternionf& orientation,
67  cv::Mat& image_out);
68 
69  void setCameraMatrices(cv::Matx33d K_, cv::Mat D_);
70 
71  void setPattern(cv::Size grid_size_, float square_size_, Pattern pattern_type_, cv::Point3f offset_ = cv::Point3f());
72 
73 public:
74  cv::Matx33d K;
75  cv::Mat D;
76  cv::Mat rvec, tvec, R;
77 
79  cv::Size grid_size;
80  float square_size;
82 };
83 
84 #endif
void convertCVtoEigen(cv::Mat &tvec, cv::Mat &R, Eigen::Vector3f &translation, Eigen::Quaternionf &orientation)
std::vector< cv::Point3f > object_pts_t
std::vector< cv::Point2f > observation_pts_t


turtlebot_arm_kinect_calibration
Author(s): Michael Ferguson, Helen Oleynikova
autogenerated on Fri Feb 7 2020 03:56:29