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 #include "boarddetector.h"
00029 #define _USE_MATH_DEFINES
00030 #include <math.h>
00031 #include <cstdlib>
00032 #include <ctime>
00033 #include <cassert>
00034 #include <fstream>
00035 #include <opencv2/calib3d/calib3d.hpp>
00036 using namespace std;
00037 using namespace cv;
00038 namespace aruco {
00041 BoardDetector::BoardDetector(bool setYPerpendicular) {
00042 _setYPerpendicular = setYPerpendicular;
00043 _areParamsSet = false;
00044 repj_err_thres = -1;
00045 }
00049 void BoardDetector::setParams(const BoardConfiguration &bc, const CameraParameters &cp, float markerSizeMeters) {
00050 _camParams = cp;
00051 _markerSize = markerSizeMeters;
00052 _bconf = bc;
00053 _areParamsSet = true;
00054 }
00059 void BoardDetector::setParams(const BoardConfiguration &bc) {
00060 _bconf = bc;
00061 _areParamsSet = true;
00062 }
00063
00068 float BoardDetector::detect(const cv::Mat &im) throw(cv::Exception) {
00069 _mdetector.detect(im, _vmarkers);
00070
00071 float res;
00072
00073 if (_camParams.isValid())
00074 res = detect(_vmarkers, _bconf, _boardDetected, _camParams.CameraMatrix, _camParams.Distorsion, _markerSize);
00075 else
00076 res = detect(_vmarkers, _bconf, _boardDetected);
00077 return res;
00078 }
00083 float BoardDetector::detect(const vector< Marker > &detectedMarkers, const BoardConfiguration &BConf, Board &Bdetected, const CameraParameters &cp,
00084 float markerSizeMeters) throw(cv::Exception) {
00085 return detect(detectedMarkers, BConf, Bdetected, cp.CameraMatrix, cp.Distorsion, markerSizeMeters);
00086 }
00091 float BoardDetector::detect(const vector< Marker > &detectedMarkers, const BoardConfiguration &BConf, Board &Bdetected, Mat camMatrix, Mat distCoeff,
00092 float markerSizeMeters) throw(cv::Exception) {
00093 if (BConf.size() == 0)
00094 throw cv::Exception(8881, "BoardDetector::detect", "Invalid BoardConfig that is empty", __FILE__, __LINE__);
00095 if (BConf[0].size() < 2)
00096 throw cv::Exception(8881, "BoardDetector::detect", "Invalid BoardConfig that is empty 2", __FILE__, __LINE__);
00097
00098 float ssize;
00099 if (BConf.mInfoType == BoardConfiguration::PIX && markerSizeMeters > 0)
00100 ssize = markerSizeMeters;
00101 else if (BConf.mInfoType == BoardConfiguration::METERS) {
00102 ssize = cv::norm(BConf[0][0] - BConf[0][1]);
00103 }
00104
00105
00106 Bdetected.clear();
00108 for (unsigned int i = 0; i < detectedMarkers.size(); i++) {
00109 int idx = BConf.getIndexOfMarkerId(detectedMarkers[i].id);
00110 if (idx != -1) {
00111 Bdetected.push_back(detectedMarkers[i]);
00112 Bdetected.back().ssize = ssize;
00113 }
00114 }
00115
00116 Bdetected.conf = BConf;
00117
00118
00119 bool hasEnoughInfoForRTvecCalculation = false;
00120 if (Bdetected.size() >= 1) {
00121 if (camMatrix.rows != 0) {
00122 if (markerSizeMeters > 0 && BConf.mInfoType == BoardConfiguration::PIX)
00123 hasEnoughInfoForRTvecCalculation = true;
00124 else if (BConf.mInfoType == BoardConfiguration::METERS)
00125 hasEnoughInfoForRTvecCalculation = true;
00126 }
00127 }
00128
00129
00130 if (hasEnoughInfoForRTvecCalculation) {
00131
00132
00133 double marker_meter_per_pix = 0;
00134 if (BConf.mInfoType == BoardConfiguration::PIX)
00135 marker_meter_per_pix = markerSizeMeters / cv::norm(BConf[0][0] - BConf[0][1]);
00136 else
00137 marker_meter_per_pix = 1;
00138
00139
00140 vector< cv::Point3f > objPoints;
00141 vector< cv::Point2f > imagePoints;
00142 for (size_t i = 0; i < Bdetected.size(); i++) {
00143 int idx = Bdetected.conf.getIndexOfMarkerId(Bdetected[i].id);
00144 assert(idx != -1);
00145 for (int p = 0; p < 4; p++) {
00146 imagePoints.push_back(Bdetected[i][p]);
00147 const aruco::MarkerInfo &Minfo = Bdetected.conf.getMarkerInfo(Bdetected[i].id);
00148 objPoints.push_back(Minfo[p] * marker_meter_per_pix);
00149
00150 }
00151 }
00152 if (distCoeff.total() == 0)
00153 distCoeff = cv::Mat::zeros(1, 4, CV_32FC1);
00154
00155
00156
00157
00158
00159 cv::Mat rvec, tvec;
00160 cv::solvePnP(objPoints, imagePoints, camMatrix, distCoeff, rvec, tvec);
00161 rvec.convertTo(Bdetected.Rvec, CV_32FC1);
00162 tvec.convertTo(Bdetected.Tvec, CV_32FC1);
00163
00164
00165 {
00166 vector< cv::Point2f > reprojected;
00167 cv::projectPoints(objPoints, rvec, tvec, camMatrix, distCoeff, reprojected);
00168 double errSum = 0;
00169
00170 for (size_t i = 0; i < reprojected.size(); i++) {
00171 errSum += cv::norm(reprojected[i] - imagePoints[i]);
00172 }
00173
00174 }
00175
00176 if (repj_err_thres > 0) {
00177 vector< cv::Point2f > reprojected;
00178 cv::projectPoints(objPoints, rvec, tvec, camMatrix, distCoeff, reprojected);
00179
00180 vector< int > pointsThatPassTest;
00181
00182 for (size_t i = 0; i < reprojected.size(); i++) {
00183 float err = cv::norm(reprojected[i] - imagePoints[i]);
00184 if (err < repj_err_thres)
00185 pointsThatPassTest.push_back(i);
00186 }
00187
00188
00189 vector< cv::Point3f > objPoints_filtered;
00190 vector< cv::Point2f > imagePoints_filtered;
00191 for (size_t i = 0; i < pointsThatPassTest.size(); i++) {
00192 objPoints_filtered.push_back(objPoints[pointsThatPassTest[i]]);
00193 imagePoints_filtered.push_back(imagePoints[pointsThatPassTest[i]]);
00194 }
00195
00196 cv::solvePnP(objPoints_filtered, imagePoints_filtered, camMatrix, distCoeff, rvec, tvec);
00197 rvec.convertTo(Bdetected.Rvec, CV_32FC1);
00198 tvec.convertTo(Bdetected.Tvec, CV_32FC1);
00199 }
00200
00201
00202
00203 if (_setYPerpendicular)
00204 rotateXAxis(Bdetected.Rvec);
00205
00206
00207 }
00208
00209 float prob = float(Bdetected.size()) / double(Bdetected.conf.size());
00210 return prob;
00211 }
00212
00213 void BoardDetector::rotateXAxis(Mat &rotation) {
00214 cv::Mat R(3, 3, CV_32FC1);
00215 Rodrigues(rotation, R);
00216
00217 cv::Mat RX = cv::Mat::eye(3, 3, CV_32FC1);
00218 float angleRad = -M_PI / 2;
00219 RX.at< float >(1, 1) = cos(angleRad);
00220 RX.at< float >(1, 2) = -sin(angleRad);
00221 RX.at< float >(2, 1) = sin(angleRad);
00222 RX.at< float >(2, 2) = cos(angleRad);
00223
00224 R = R * RX;
00225
00226 Rodrigues(R, rotation);
00227 }
00228
00231 Board BoardDetector::detect(const cv::Mat &Image, const BoardConfiguration &bc, const CameraParameters &cp, float markerSizeMeters) {
00232 BoardDetector BD;
00233 BD.setParams(bc, cp, markerSizeMeters);
00234 BD.detect(Image);
00235 return BD.getDetectedBoard();
00236 }
00237 };