29 #define _USE_MATH_DEFINES 35 #include <opencv2/calib3d/calib3d.hpp> 41 BoardDetector::BoardDetector(
bool setYPerpendicular) {
42 _setYPerpendicular = setYPerpendicular;
43 _areParamsSet =
false;
51 _markerSize = markerSizeMeters;
68 float BoardDetector::detect(
const cv::Mat &im)
throw(cv::Exception) {
69 _mdetector.detect(im, _vmarkers);
73 if (_camParams.isValid())
74 res = detect(_vmarkers, _bconf, _boardDetected, _camParams.CameraMatrix, _camParams.Distorsion, _markerSize);
76 res = detect(_vmarkers, _bconf, _boardDetected);
84 float markerSizeMeters)
throw(cv::Exception) {
85 return detect(detectedMarkers, BConf, Bdetected, cp.CameraMatrix, cp.Distorsion, markerSizeMeters);
91 float BoardDetector::detect(
const vector< Marker > &detectedMarkers,
const BoardConfiguration &BConf,
Board &Bdetected, Mat camMatrix, Mat distCoeff,
92 float markerSizeMeters)
throw(cv::Exception) {
93 if (BConf.size() == 0)
94 throw cv::Exception(8881,
"BoardDetector::detect",
"Invalid BoardConfig that is empty", __FILE__, __LINE__);
95 if (BConf[0].size() < 2)
96 throw cv::Exception(8881,
"BoardDetector::detect",
"Invalid BoardConfig that is empty 2", __FILE__, __LINE__);
99 if (BConf.
mInfoType == BoardConfiguration::PIX && markerSizeMeters > 0)
100 ssize = markerSizeMeters;
101 else if (BConf.
mInfoType == BoardConfiguration::METERS) {
102 ssize = cv::norm(BConf[0][0] - BConf[0][1]);
108 for (
unsigned int i = 0; i < detectedMarkers.size(); i++) {
111 Bdetected.push_back(detectedMarkers[i]);
112 Bdetected.back().ssize = ssize;
116 Bdetected.
conf = BConf;
119 bool hasEnoughInfoForRTvecCalculation =
false;
120 if (Bdetected.size() >= 1) {
121 if (camMatrix.rows != 0) {
122 if (markerSizeMeters > 0 && BConf.
mInfoType == BoardConfiguration::PIX)
123 hasEnoughInfoForRTvecCalculation =
true;
124 else if (BConf.
mInfoType == BoardConfiguration::METERS)
125 hasEnoughInfoForRTvecCalculation =
true;
130 if (hasEnoughInfoForRTvecCalculation) {
133 double marker_meter_per_pix = 0;
134 if (BConf.
mInfoType == BoardConfiguration::PIX)
135 marker_meter_per_pix = markerSizeMeters / cv::norm(BConf[0][0] - BConf[0][1]);
137 marker_meter_per_pix = 1;
140 vector< cv::Point3f > objPoints;
141 vector< cv::Point2f > imagePoints;
142 for (
size_t i = 0; i < Bdetected.size(); i++) {
145 for (
int p = 0; p < 4; p++) {
146 imagePoints.push_back(Bdetected[i][p]);
148 objPoints.push_back(Minfo[p] * marker_meter_per_pix);
152 if (distCoeff.total() == 0)
153 distCoeff = cv::Mat::zeros(1, 4, CV_32FC1);
160 cv::solvePnP(objPoints, imagePoints, camMatrix, distCoeff, rvec, tvec);
161 rvec.convertTo(Bdetected.
Rvec, CV_32FC1);
162 tvec.convertTo(Bdetected.
Tvec, CV_32FC1);
166 vector< cv::Point2f > reprojected;
167 cv::projectPoints(objPoints, rvec, tvec, camMatrix, distCoeff, reprojected);
170 for (
size_t i = 0; i < reprojected.size(); i++) {
171 errSum += cv::norm(reprojected[i] - imagePoints[i]);
176 if (repj_err_thres > 0) {
177 vector< cv::Point2f > reprojected;
178 cv::projectPoints(objPoints, rvec, tvec, camMatrix, distCoeff, reprojected);
180 vector< int > pointsThatPassTest;
182 for (
size_t i = 0; i < reprojected.size(); i++) {
183 float err = cv::norm(reprojected[i] - imagePoints[i]);
184 if (err < repj_err_thres)
185 pointsThatPassTest.push_back(i);
189 vector< cv::Point3f > objPoints_filtered;
190 vector< cv::Point2f > imagePoints_filtered;
191 for (
size_t i = 0; i < pointsThatPassTest.size(); i++) {
192 objPoints_filtered.push_back(objPoints[pointsThatPassTest[i]]);
193 imagePoints_filtered.push_back(imagePoints[pointsThatPassTest[i]]);
196 cv::solvePnP(objPoints_filtered, imagePoints_filtered, camMatrix, distCoeff, rvec, tvec);
197 rvec.convertTo(Bdetected.
Rvec, CV_32FC1);
198 tvec.convertTo(Bdetected.
Tvec, CV_32FC1);
203 if (_setYPerpendicular)
204 rotateXAxis(Bdetected.
Rvec);
209 float prob = float(Bdetected.size()) /
double(Bdetected.
conf.size());
213 void BoardDetector::rotateXAxis(Mat &rotation) {
214 cv::Mat R(3, 3, CV_32FC1);
215 Rodrigues(rotation, R);
217 cv::Mat RX = cv::Mat::eye(3, 3, CV_32FC1);
218 float angleRad = -M_PI / 2;
219 RX.at<
float >(1, 1) = cos(angleRad);
220 RX.at<
float >(1, 2) = -sin(angleRad);
221 RX.at<
float >(2, 1) = sin(angleRad);
222 RX.at<
float >(2, 2) = cos(angleRad);
226 Rodrigues(R, rotation);
Board & getDetectedBoard()
const MarkerInfo & getMarkerInfo(int id) const
int getIndexOfMarkerId(int id) const
void setParams(const BoardConfiguration &bc, const CameraParameters &cp, float markerSizeMeters=-1)
This class detects AR boards Version 1.2 There are two modes for board detection. First...
float detect(const cv::Mat &im)
Parameters of the camera.
This class defines a board with several markers. A Board contains several markers so that they are mo...