Go to the documentation of this file.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 #ifndef _Aruco_Marker_H
00029 #define _Aruco_Marker_H
00030 #include <vector>
00031 #include <iostream>
00032 #include <opencv2/opencv.hpp>
00033 #include "exports.h"
00034 #include "cameraparameters.h"
00035 using namespace std;
00036 namespace aruco {
00041 class ARUCO_EXPORTS Marker:
00042 public std::vector<cv::Point2f>
00043 {
00044 public:
00045
00046 int id;
00047
00048 float ssize;
00049
00050 cv::Mat Rvec,Tvec;
00051
00052
00053 cv::Point marker_center_img;
00054 cv::Point3f marker_world_position;
00055
00056
00059 Marker();
00062 Marker(const Marker &M);
00065 Marker(const std::vector<cv::Point2f> &corners,int _id=-1);
00066
00070 Marker(const std::vector<cv::Point2f> &corners,int _id=-1, float _ssize=-1);
00071
00074 ~Marker() {}
00077 bool isValid()const{return id!=-1 && size()==4;}
00078
00081 void draw(cv::Mat &in, cv::Scalar color, int lineWidth=1,bool writeId=true)const;
00082
00085 void draw_size(cv::Mat &in, cv::Scalar color, int lineWidth=1,bool writeId=true)const;
00086
00092 void calculateExtrinsics(float markerSize,const CameraParameters &CP,bool setYPerperdicular=true)throw(cv::Exception);
00099 void calculateExtrinsics(float markerSize,cv::Mat CameraMatrix,cv::Mat Distorsion=cv::Mat(),bool setYPerperdicular=true)throw(cv::Exception);
00100
00104 void glGetModelViewMatrix( double modelview_matrix[16])throw(cv::Exception);
00105
00116 void OgreGetPoseParameters( double position[3], double orientation[4] )throw(cv::Exception);
00117
00120 cv::Point2f getCenter()const;
00123 float getPerimeter()const;
00126 float getArea()const;
00131 friend bool operator<(const Marker &M1,const Marker&M2)
00132 {
00133 return M1.id<M2.id;
00134 }
00137 friend ostream & operator<<(ostream &str,const Marker &M)
00138 {
00139
00140 str<<M.id<<"=";
00141 for (int i=0;i<4;i++)
00142 str<<"("<<M[i].x<< ","<<M[i].y<<") ";
00143 str<<"Txyz=";
00144 for (int i=0;i<3;i++)
00145 str<<M.Tvec.ptr<float>(0)[i]<<" ";
00146 str<<"Rxyz=";
00147 for (int i=0;i<3;i++)
00148 str<<M.Rvec.ptr<float>(0)[i]<<" ";
00149
00150 return str;
00151 }
00152
00153
00154 private:
00155 void rotateXAxis(cv::Mat &rotation);
00156
00157 };
00158
00159 }
00160 #endif