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 "marker.h"
00029 #define _USE_MATH_DEFINES
00030 #include <math.h>
00031 #include <cstdio>
00032 #include <opencv2/calib3d/calib3d.hpp>
00033 #include <opencv2/highgui/highgui.hpp>
00034 #include <opencv2/imgproc/imgproc.hpp>
00035 using namespace cv;
00036 namespace aruco {
00040 Marker::Marker() {
00041 id = -1;
00042 ssize = -1;
00043 Rvec.create(3, 1, CV_32FC1);
00044 Tvec.create(3, 1, CV_32FC1);
00045 for (int i = 0; i < 3; i++)
00046 Tvec.at< float >(i, 0) = Rvec.at< float >(i, 0) = -999999;
00047 }
00051 Marker::Marker(const Marker &M) : std::vector< cv::Point2f >(M) {
00052 M.Rvec.copyTo(Rvec);
00053 M.Tvec.copyTo(Tvec);
00054 id = M.id;
00055 ssize = M.ssize;
00056 }
00057
00061 Marker::Marker(const std::vector< cv::Point2f > &corners, int _id) : std::vector< cv::Point2f >(corners) {
00062 id = _id;
00063 ssize = -1;
00064 Rvec.create(3, 1, CV_32FC1);
00065 Tvec.create(3, 1, CV_32FC1);
00066 for (int i = 0; i < 3; i++)
00067 Tvec.at< float >(i, 0) = Rvec.at< float >(i, 0) = -999999;
00068 }
00069
00073 void Marker::glGetModelViewMatrix(double modelview_matrix[16]) throw(cv::Exception) {
00074
00075 bool invalid = false;
00076 for (int i = 0; i < 3 && !invalid; i++) {
00077 if (Tvec.at< float >(i, 0) != -999999)
00078 invalid |= false;
00079 if (Rvec.at< float >(i, 0) != -999999)
00080 invalid |= false;
00081 }
00082 if (invalid)
00083 throw cv::Exception(9003, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
00084 Mat Rot(3, 3, CV_32FC1), Jacob;
00085 Rodrigues(Rvec, Rot, Jacob);
00086
00087 double para[3][4];
00088 for (int i = 0; i < 3; i++)
00089 for (int j = 0; j < 3; j++)
00090 para[i][j] = Rot.at< float >(i, j);
00091
00092 para[0][3] = Tvec.at< float >(0, 0);
00093 para[1][3] = Tvec.at< float >(1, 0);
00094 para[2][3] = Tvec.at< float >(2, 0);
00095 double scale = 1;
00096
00097 modelview_matrix[0 + 0 * 4] = para[0][0];
00098
00099 modelview_matrix[0 + 1 * 4] = para[0][1];
00100 modelview_matrix[0 + 2 * 4] = para[0][2];
00101 modelview_matrix[0 + 3 * 4] = para[0][3];
00102
00103 modelview_matrix[1 + 0 * 4] = para[1][0];
00104 modelview_matrix[1 + 1 * 4] = para[1][1];
00105 modelview_matrix[1 + 2 * 4] = para[1][2];
00106 modelview_matrix[1 + 3 * 4] = para[1][3];
00107
00108 modelview_matrix[2 + 0 * 4] = -para[2][0];
00109 modelview_matrix[2 + 1 * 4] = -para[2][1];
00110 modelview_matrix[2 + 2 * 4] = -para[2][2];
00111 modelview_matrix[2 + 3 * 4] = -para[2][3];
00112 modelview_matrix[3 + 0 * 4] = 0.0;
00113 modelview_matrix[3 + 1 * 4] = 0.0;
00114 modelview_matrix[3 + 2 * 4] = 0.0;
00115 modelview_matrix[3 + 3 * 4] = 1.0;
00116 if (scale != 0.0) {
00117 modelview_matrix[12] *= scale;
00118 modelview_matrix[13] *= scale;
00119 modelview_matrix[14] *= scale;
00120 }
00121 }
00122
00123
00124
00125
00126
00127
00128 void Marker::OgreGetPoseParameters(double position[3], double orientation[4]) throw(cv::Exception) {
00129
00130
00131 bool invalid = false;
00132 for (int i = 0; i < 3 && !invalid; i++) {
00133 if (Tvec.at< float >(i, 0) != -999999)
00134 invalid |= false;
00135 if (Rvec.at< float >(i, 0) != -999999)
00136 invalid |= false;
00137 }
00138 if (invalid)
00139 throw cv::Exception(9003, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
00140
00141
00142 position[0] = -Tvec.ptr< float >(0)[0];
00143 position[1] = -Tvec.ptr< float >(0)[1];
00144 position[2] = +Tvec.ptr< float >(0)[2];
00145
00146
00147 cv::Mat Rot(3, 3, CV_32FC1);
00148 cv::Rodrigues(Rvec, Rot);
00149
00150
00151 double stAxes[3][3];
00152
00153 stAxes[0][0] = -Rot.at< float >(0, 0);
00154 stAxes[0][1] = -Rot.at< float >(1, 0);
00155 stAxes[0][2] = +Rot.at< float >(2, 0);
00156
00157 stAxes[1][0] = -Rot.at< float >(0, 1);
00158 stAxes[1][1] = -Rot.at< float >(1, 1);
00159 stAxes[1][2] = +Rot.at< float >(2, 1);
00160
00161 stAxes[2][0] = stAxes[0][1] * stAxes[1][2] - stAxes[0][2] * stAxes[1][1];
00162 stAxes[2][1] = -stAxes[0][0] * stAxes[1][2] + stAxes[0][2] * stAxes[1][0];
00163 stAxes[2][2] = stAxes[0][0] * stAxes[1][1] - stAxes[0][1] * stAxes[1][0];
00164
00165
00166 double axes[3][3];
00167 axes[0][0] = stAxes[0][0];
00168 axes[1][0] = stAxes[0][1];
00169 axes[2][0] = stAxes[0][2];
00170
00171 axes[0][1] = stAxes[1][0];
00172 axes[1][1] = stAxes[1][1];
00173 axes[2][1] = stAxes[1][2];
00174
00175 axes[0][2] = stAxes[2][0];
00176 axes[1][2] = stAxes[2][1];
00177 axes[2][2] = stAxes[2][2];
00178
00179
00180
00181 double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
00182 double fRoot;
00183
00184 if (fTrace > 0.0) {
00185
00186 fRoot = sqrt(fTrace + 1.0);
00187 orientation[0] = 0.5 * fRoot;
00188 fRoot = 0.5 / fRoot;
00189 orientation[1] = (axes[2][1] - axes[1][2]) * fRoot;
00190 orientation[2] = (axes[0][2] - axes[2][0]) * fRoot;
00191 orientation[3] = (axes[1][0] - axes[0][1]) * fRoot;
00192 } else {
00193
00194 static unsigned int s_iNext[3] = {1, 2, 0};
00195 unsigned int i = 0;
00196 if (axes[1][1] > axes[0][0])
00197 i = 1;
00198 if (axes[2][2] > axes[i][i])
00199 i = 2;
00200 unsigned int j = s_iNext[i];
00201 unsigned int k = s_iNext[j];
00202
00203 fRoot = sqrt(axes[i][i] - axes[j][j] - axes[k][k] + 1.0);
00204 double *apkQuat[3] = {&orientation[1], &orientation[2], &orientation[3]};
00205 *apkQuat[i] = 0.5 * fRoot;
00206 fRoot = 0.5 / fRoot;
00207 orientation[0] = (axes[k][j] - axes[j][k]) * fRoot;
00208 *apkQuat[j] = (axes[j][i] + axes[i][j]) * fRoot;
00209 *apkQuat[k] = (axes[k][i] + axes[i][k]) * fRoot;
00210 }
00211 }
00212
00213
00214
00215 void Marker::draw(Mat &in, Scalar color, int lineWidth, bool writeId) const {
00216 if (size() != 4)
00217 return;
00218 cv::line(in, (*this)[0], (*this)[1], color, lineWidth, CV_AA);
00219 cv::line(in, (*this)[1], (*this)[2], color, lineWidth, CV_AA);
00220 cv::line(in, (*this)[2], (*this)[3], color, lineWidth, CV_AA);
00221 cv::line(in, (*this)[3], (*this)[0], color, lineWidth, CV_AA);
00222 cv::rectangle(in, (*this)[0] - Point2f(2, 2), (*this)[0] + Point2f(2, 2), Scalar(0, 0, 255, 255), lineWidth, CV_AA);
00223 cv::rectangle(in, (*this)[1] - Point2f(2, 2), (*this)[1] + Point2f(2, 2), Scalar(0, 255, 0, 255), lineWidth, CV_AA);
00224 cv::rectangle(in, (*this)[2] - Point2f(2, 2), (*this)[2] + Point2f(2, 2), Scalar(255, 0, 0, 255), lineWidth, CV_AA);
00225 if (writeId) {
00226 char cad[100];
00227 sprintf(cad, "id=%d", id);
00228
00229 Point cent(0, 0);
00230 for (int i = 0; i < 4; i++) {
00231 cent.x += (*this)[i].x;
00232 cent.y += (*this)[i].y;
00233 }
00234 cent.x /= 4.;
00235 cent.y /= 4.;
00236 putText(in, cad, cent, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255 - color[0], 255 - color[1], 255 - color[2], 255), 2);
00237 }
00238 }
00239
00242 void Marker::calculateExtrinsics(float markerSize, const CameraParameters &CP, bool setYPerpendicular) throw(cv::Exception) {
00243 if (!CP.isValid())
00244 throw cv::Exception(9004, "!CP.isValid(): invalid camera parameters. It is not possible to calculate extrinsics", "calculateExtrinsics", __FILE__,
00245 __LINE__);
00246 calculateExtrinsics(markerSize, CP.CameraMatrix, CP.Distorsion, setYPerpendicular);
00247 }
00248
00249 void print(cv::Point3f p, string cad) { cout << cad << " " << p.x << " " << p.y << " " << p.z << endl; }
00252 void Marker::calculateExtrinsics(float markerSizeMeters, cv::Mat camMatrix, cv::Mat distCoeff, bool setYPerpendicular) throw(cv::Exception) {
00253 if (!isValid())
00254 throw cv::Exception(9004, "!isValid(): invalid marker. It is not possible to calculate extrinsics", "calculateExtrinsics", __FILE__, __LINE__);
00255 if (markerSizeMeters <= 0)
00256 throw cv::Exception(9004, "markerSize<=0: invalid markerSize", "calculateExtrinsics", __FILE__, __LINE__);
00257 if (camMatrix.rows == 0 || camMatrix.cols == 0)
00258 throw cv::Exception(9004, "CameraMatrix is empty", "calculateExtrinsics", __FILE__, __LINE__);
00259
00260 double halfSize = markerSizeMeters / 2.;
00261 cv::Mat ObjPoints(4, 3, CV_32FC1);
00262 ObjPoints.at< float >(1, 0) = -halfSize;
00263 ObjPoints.at< float >(1, 1) = halfSize;
00264 ObjPoints.at< float >(1, 2) = 0;
00265 ObjPoints.at< float >(2, 0) = halfSize;
00266 ObjPoints.at< float >(2, 1) = halfSize;
00267 ObjPoints.at< float >(2, 2) = 0;
00268 ObjPoints.at< float >(3, 0) = halfSize;
00269 ObjPoints.at< float >(3, 1) = -halfSize;
00270 ObjPoints.at< float >(3, 2) = 0;
00271 ObjPoints.at< float >(0, 0) = -halfSize;
00272 ObjPoints.at< float >(0, 1) = -halfSize;
00273 ObjPoints.at< float >(0, 2) = 0;
00274
00275 cv::Mat ImagePoints(4, 2, CV_32FC1);
00276
00277
00278 for (int c = 0; c < 4; c++) {
00279 ImagePoints.at< float >(c, 0) = ((*this)[c].x);
00280 ImagePoints.at< float >(c, 1) = ((*this)[c].y);
00281 }
00282
00283 cv::Mat raux, taux;
00284 cv::solvePnP(ObjPoints, ImagePoints, camMatrix, distCoeff, raux, taux);
00285 raux.convertTo(Rvec, CV_32F);
00286 taux.convertTo(Tvec, CV_32F);
00287
00288 if (setYPerpendicular)
00289 rotateXAxis(Rvec);
00290 ssize = markerSizeMeters;
00291
00292 }
00293
00294
00298 void Marker::rotateXAxis(Mat &rotation) {
00299 cv::Mat R(3, 3, CV_32F);
00300 Rodrigues(rotation, R);
00301
00302 cv::Mat RX = cv::Mat::eye(3, 3, CV_32F);
00303 float angleRad = M_PI / 2;
00304 RX.at< float >(1, 1) = cos(angleRad);
00305 RX.at< float >(1, 2) = -sin(angleRad);
00306 RX.at< float >(2, 1) = sin(angleRad);
00307 RX.at< float >(2, 2) = cos(angleRad);
00308
00309 R = R * RX;
00310
00311 Rodrigues(R, rotation);
00312 }
00313
00314
00315
00318 cv::Point2f Marker::getCenter() const {
00319 cv::Point2f cent(0, 0);
00320 for (size_t i = 0; i < size(); i++) {
00321 cent.x += (*this)[i].x;
00322 cent.y += (*this)[i].y;
00323 }
00324 cent.x /= float(size());
00325 cent.y /= float(size());
00326 return cent;
00327 }
00328
00331 float Marker::getArea() const {
00332 assert(size() == 4);
00333
00334 cv::Point2f v01 = (*this)[1] - (*this)[0];
00335 cv::Point2f v03 = (*this)[3] - (*this)[0];
00336 float area1 = fabs(v01.x * v03.y - v01.y * v03.x);
00337 cv::Point2f v21 = (*this)[1] - (*this)[2];
00338 cv::Point2f v23 = (*this)[3] - (*this)[2];
00339 float area2 = fabs(v21.x * v23.y - v21.y * v23.x);
00340 return (area2 + area1) / 2.;
00341 }
00344 float Marker::getPerimeter() const {
00345 assert(size() == 4);
00346 float sum = 0;
00347 for (int i = 0; i < 4; i++)
00348 sum += norm((*this)[i] - (*this)[(i + 1) % 4]);
00349 return sum;
00350 }
00351 }