29 #define _USE_MATH_DEFINES    32 #include <opencv2/calib3d/calib3d.hpp>    33 #include <opencv2/highgui/highgui.hpp>    34 #include <opencv2/imgproc/imgproc.hpp>    43     Rvec.create(3, 1, CV_32FC1);
    44     Tvec.create(3, 1, CV_32FC1);
    45     for (
int i = 0; i < 3; i++)
    46         Tvec.at< 
float >(i, 0) = Rvec.at< 
float >(i, 0) = -999999;
    51 Marker::Marker(
int _id) {
    54     Rvec.create(3, 1, CV_32FC1);
    55     Tvec.create(3, 1, CV_32FC1);
    56     for (
int i = 0; i < 3; i++)
    57         Tvec.at< 
float >(i, 0) = Rvec.at< 
float >(i, 0) = -999999;
    62 Marker::Marker(
const Marker &M) : 
std::vector< 
cv::Point2f >(M) {
    72 Marker::Marker(
const std::vector< cv::Point2f > &corners, 
int _id) : 
std::vector< 
cv::Point2f >(corners) {
    75     Rvec.create(3, 1, CV_32FC1);
    76     Tvec.create(3, 1, CV_32FC1);
    77     for (
int i = 0; i < 3; i++)
    78         Tvec.at< 
float >(i, 0) = 
Rvec.at< 
float >(i, 0) = -999999;
    87     for (
int i = 0; i < 3 && !invalid; i++) {
    88         if (
Tvec.at< 
float >(i, 0) != -999999)
    90         if (
Rvec.at< 
float >(i, 0) != -999999)
    94         throw cv::Exception(9003, 
"extrinsic parameters are not set", 
"Marker::getModelViewMatrix", __FILE__, __LINE__);
    95     Mat Rot(3, 3, CV_32FC1), Jacob;
    96     Rodrigues(
Rvec, Rot, Jacob);
    99     for (
int i = 0; i < 3; i++)
   100         for (
int j = 0; j < 3; j++)
   101             para[i][j] = Rot.at< 
float >(i, j);
   103     para[0][3] = 
Tvec.at< 
float >(0, 0);
   104     para[1][3] = 
Tvec.at< 
float >(1, 0);
   105     para[2][3] = 
Tvec.at< 
float >(2, 0);
   108     modelview_matrix[0 + 0 * 4] = para[0][0];
   110     modelview_matrix[0 + 1 * 4] = para[0][1];
   111     modelview_matrix[0 + 2 * 4] = para[0][2];
   112     modelview_matrix[0 + 3 * 4] = para[0][3];
   114     modelview_matrix[1 + 0 * 4] = para[1][0];
   115     modelview_matrix[1 + 1 * 4] = para[1][1];
   116     modelview_matrix[1 + 2 * 4] = para[1][2];
   117     modelview_matrix[1 + 3 * 4] = para[1][3];
   119     modelview_matrix[2 + 0 * 4] = -para[2][0];
   120     modelview_matrix[2 + 1 * 4] = -para[2][1];
   121     modelview_matrix[2 + 2 * 4] = -para[2][2];
   122     modelview_matrix[2 + 3 * 4] = -para[2][3];
   123     modelview_matrix[3 + 0 * 4] = 0.0;
   124     modelview_matrix[3 + 1 * 4] = 0.0;
   125     modelview_matrix[3 + 2 * 4] = 0.0;
   126     modelview_matrix[3 + 3 * 4] = 1.0;
   128         modelview_matrix[12] *= scale;
   129         modelview_matrix[13] *= scale;
   130         modelview_matrix[14] *= scale;
   142     bool invalid = 
false;
   143     for (
int i = 0; i < 3 && !invalid; i++) {
   144         if (
Tvec.at< 
float >(i, 0) != -999999)
   146         if (
Rvec.at< 
float >(i, 0) != -999999)
   150         throw cv::Exception(9003, 
"extrinsic parameters are not set", 
"Marker::getModelViewMatrix", __FILE__, __LINE__);
   153     position[0] = -
Tvec.ptr< 
float >(0)[0];
   154     position[1] = -
Tvec.ptr< 
float >(0)[1];
   155     position[2] = +
Tvec.ptr< 
float >(0)[2];
   158     cv::Mat Rot(3, 3, CV_32FC1);
   159     cv::Rodrigues(
Rvec, Rot);
   164     stAxes[0][0] = -Rot.at< 
float >(0, 0);
   165     stAxes[0][1] = -Rot.at< 
float >(1, 0);
   166     stAxes[0][2] = +Rot.at< 
float >(2, 0);
   168     stAxes[1][0] = -Rot.at< 
float >(0, 1);
   169     stAxes[1][1] = -Rot.at< 
float >(1, 1);
   170     stAxes[1][2] = +Rot.at< 
float >(2, 1);
   172     stAxes[2][0] = stAxes[0][1] * stAxes[1][2] - stAxes[0][2] * stAxes[1][1];
   173     stAxes[2][1] = -stAxes[0][0] * stAxes[1][2] + stAxes[0][2] * stAxes[1][0];
   174     stAxes[2][2] = stAxes[0][0] * stAxes[1][1] - stAxes[0][1] * stAxes[1][0];
   178     axes[0][0] = stAxes[0][0];
   179     axes[1][0] = stAxes[0][1];
   180     axes[2][0] = stAxes[0][2];
   182     axes[0][1] = stAxes[1][0];
   183     axes[1][1] = stAxes[1][1];
   184     axes[2][1] = stAxes[1][2];
   186     axes[0][2] = stAxes[2][0];
   187     axes[1][2] = stAxes[2][1];
   188     axes[2][2] = stAxes[2][2];
   192     double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
   197         fRoot = 
sqrt(fTrace + 1.0); 
   198         orientation[0] = 0.5 * fRoot;
   200         orientation[1] = (axes[2][1] - axes[1][2]) * fRoot;
   201         orientation[2] = (axes[0][2] - axes[2][0]) * fRoot;
   202         orientation[3] = (axes[1][0] - axes[0][1]) * fRoot;
   205         static unsigned int s_iNext[3] = {1, 2, 0};
   207         if (axes[1][1] > axes[0][0])
   209         if (axes[2][2] > axes[i][i])
   211         unsigned int j = s_iNext[i];
   212         unsigned int k = s_iNext[j];
   214         fRoot = 
sqrt(axes[i][i] - axes[j][j] - axes[k][k] + 1.0);
   215         double *apkQuat[3] = {&orientation[1], &orientation[2], &orientation[3]};
   216         *apkQuat[i] = 0.5 * fRoot;
   218         orientation[0] = (axes[k][j] - axes[j][k]) * fRoot;
   219         *apkQuat[j] = (axes[j][i] + axes[i][j]) * fRoot;
   220         *apkQuat[k] = (axes[k][i] + axes[i][k]) * fRoot;
   226 void Marker::draw(Mat &in, Scalar color, 
int lineWidth, 
bool writeId)
 const {
   229     cv::line(in, (*
this)[0], (*
this)[1], color, lineWidth, CV_AA);
   230     cv::line(in, (*
this)[1], (*
this)[2], color, lineWidth, CV_AA);
   231     cv::line(in, (*
this)[2], (*
this)[3], color, lineWidth, CV_AA);
   232     cv::line(in, (*
this)[3], (*
this)[0], color, lineWidth, CV_AA);
   233     cv::rectangle(in, (*
this)[0] - Point2f(2, 2), (*
this)[0] + Point2f(2, 2), Scalar(0, 0, 255, 255), lineWidth, CV_AA);
   234     cv::rectangle(in, (*
this)[1] - Point2f(2, 2), (*
this)[1] + Point2f(2, 2), Scalar(0, 255, 0, 255), lineWidth, CV_AA);
   235     cv::rectangle(in, (*
this)[2] - Point2f(2, 2), (*
this)[2] + Point2f(2, 2), Scalar(255, 0, 0, 255), lineWidth, CV_AA);
   238         sprintf(cad, 
"id=%d", 
id);
   241         for (
int i = 0; i < 4; i++) {
   242             cent.
x += (*this)[i].x;
   243             cent.
y += (*this)[i].y;
   247         putText(in, cad, cent, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255 - color[0], 255 - color[1], 255 - color[2], 255), 2);
   255         throw cv::Exception(9004, 
"!CP.isValid(): invalid camera parameters. It is not possible to calculate extrinsics", 
"calculateExtrinsics", __FILE__,
   260 void print(cv::Point3f p, 
string cad) { cout << cad << 
" " << p.x << 
" " << p.y << 
" " << p.z << endl; }
   265         throw cv::Exception(9004, 
"!isValid(): invalid marker. It is not possible to calculate extrinsics", 
"calculateExtrinsics", __FILE__, __LINE__);
   266     if (markerSizeMeters <= 0)
   267         throw cv::Exception(9004, 
"markerSize<=0: invalid markerSize", 
"calculateExtrinsics", __FILE__, __LINE__);
   268     if (camMatrix.rows == 0 || camMatrix.cols == 0)
   269         throw cv::Exception(9004, 
"CameraMatrix is empty", 
"calculateExtrinsics", __FILE__, __LINE__);
   271     vector<cv::Point3f> objpoints=
get3DPoints(markerSizeMeters);
   276     cv::solvePnP(objpoints, *
this, camMatrix, distCoeff, raux, taux);
   277     raux.convertTo(
Rvec, CV_32F);
   278     taux.convertTo(
Tvec, CV_32F);
   280     if (setYPerpendicular)
   282     ssize = markerSizeMeters;
   287     double halfSize = msize / 2.;
   288     return {cv::Point3f(-halfSize,halfSize,0), cv::Point3f(halfSize,halfSize,0),cv::Point3f(halfSize,-halfSize,0),cv::Point3f(-halfSize,-halfSize,0)};
   296     cv::Mat R(3, 3, CV_32F);
   297     Rodrigues(rotation, R);
   299     cv::Mat RX = cv::Mat::eye(3, 3, CV_32F);
   300     float angleRad = 3.14159265359 / 2.;
   301     RX.at< 
float >(1, 1) = 
cos(angleRad);
   302     RX.at< 
float >(1, 2) = -
sin(angleRad);
   303     RX.at< 
float >(2, 1) = 
sin(angleRad);
   304     RX.at< 
float >(2, 2) = 
cos(angleRad);
   308     Rodrigues(R, rotation);
   316     cv::Point2f cent(0, 0);
   317     for (
size_t i = 0; i < size(); i++) {
   318         cent.x += (*this)[i].x;
   319         cent.y += (*this)[i].y;
   321     cent.x /= float(size());
   322     cent.y /= float(size());
   331     cv::Point2f v01 = (*this)[1] - (*this)[0];
   332     cv::Point2f v03 = (*this)[3] - (*this)[0];
   333     float area1 = fabs(v01.x * v03.y - v01.y * v03.x);
   334     cv::Point2f v21 = (*this)[1] - (*this)[2];
   335     cv::Point2f v23 = (*this)[3] - (*this)[2];
   336     float area2 = fabs(v21.x * v23.y - v21.y * v23.x);
   337     return (area2 + area1) / 2.;
   344     for (
int i = 0; i < 4; i++)
   345         sum += norm((*
this)[i] - (*
this)[(i + 1) % 4]);
   350     assert(
Rvec.type()==CV_32F && 
Tvec.type()==CV_32F);
   351     str.write((
char*)&
id,
sizeof(
int));
   352     str.write((
char*)&
ssize,
sizeof(
float));
   353     str.write((
char*)
Rvec.ptr<
float>(0),3*
sizeof(
float));
   354     str.write((
char*)
Tvec.ptr<
float>(0),3*
sizeof(
float));
   357     str.write((
char*) &np, 
sizeof(np));
   358     for(
size_t i=0;i<size();i++) str.write((
char*) &at(i), 
sizeof(cv::Point2f));
   363     Rvec.create(1,3,CV_32F);
   364     Tvec.create(1,3,CV_32F);
   365     str.read((
char*)&
id,
sizeof(
int));
   366     str.read((
char*)&
ssize,
sizeof(
float));
   367     str.read((
char*)
Rvec.ptr<
float>(0),3*
sizeof(
float));
   368     str.read((
char*)
Tvec.ptr<
float>(0),3*
sizeof(
float));
   370     str.read((
char*) &np, 
sizeof(np));
   372     for(
size_t i=0;i<size();i++) str.read((
char*) &(*
this)[i], 
sizeof(cv::Point2f));
 std::vector< cv::Mat > solvePnP(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
void toStream(ostream &str) const 
static vector< cv::Point3f > get3DPoints(float msize)
void rotateXAxis(cv::Mat &rotation)
TFSIMD_FORCE_INLINE const tfScalar & x() const 
void calculateExtrinsics(float markerSize, const CameraParameters &CP, bool setYPerpendicular=true)
TFSIMD_FORCE_INLINE const tfScalar & y() const 
const CwiseUnaryOp< internal::scalar_sin_op< Scalar >, const Derived > sin() const 
This class represents a marker. It is a vector of the fours corners ot the marker. 
Parameters of the camera. 
void glGetModelViewMatrix(double modelview_matrix[16])
cv::Point2f getCenter() const 
const CwiseUnaryOp< internal::scalar_cos_op< Scalar >, const Derived > cos() const 
void draw(cv::Mat &in, cv::Scalar color, int lineWidth=1, bool writeId=true) const 
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const 
void print(cv::Point3f p, string cad)
float getPerimeter() const 
void OgreGetPoseParameters(double position[3], double orientation[4])
void fromStream(istream &str)