marker.cpp
Go to the documentation of this file.
1 /*****************************
2 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without modification, are
5 permitted provided that the following conditions are met:
6 
7  1. Redistributions of source code must retain the above copyright notice, this list of
8  conditions and the following disclaimer.
9 
10  2. Redistributions in binary form must reproduce the above copyright notice, this list
11  of conditions and the following disclaimer in the documentation and/or other materials
12  provided with the distribution.
13 
14 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
15 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
16 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
17 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
19 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
20 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
21 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
22 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 
24 The views and conclusions contained in the software and documentation are those of the
25 authors and should not be interpreted as representing official policies, either expressed
26 or implied, of Rafael Muñoz Salinas.
27 ********************************/
28 #include <aruco/marker.h>
29 #define _USE_MATH_DEFINES
30 #include <math.h>
31 #include <cstdio>
32 
33 using namespace cv;
34 namespace aruco {
38  Marker::Marker()
39  {
40  id=-1;
41  ssize=-1;
42  Rvec.create(3,1,CV_32FC1);
43  Tvec.create(3,1,CV_32FC1);
44  for (int i=0;i<3;i++)
45  Tvec.at<float>(i,0)=Rvec.at<float>(i,0)=NAN;
46  }
50  Marker::Marker(const Marker &M):std::vector<cv::Point2f>(M)
51  {
52  M.Rvec.copyTo(Rvec);
53  M.Tvec.copyTo(Tvec);
54  id=M.id;
55  ssize=M.ssize;
56  }
57 
61  Marker::Marker(const std::vector<cv::Point2f> &corners,int _id):std::vector<cv::Point2f>(corners)
62  {
63  id=_id;
64  ssize=-1;
65  Rvec.create(3,1,CV_32FC1);
66  Tvec.create(3,1,CV_32FC1);
67  for (int i=0;i<3;i++)
68  Tvec.at<float>(i,0)=Rvec.at<float>(i,0)=NAN;
69  }
70 
74  void Marker::glGetModelViewMatrix( double modelview_matrix[16])throw(cv::Exception)
75  {
76  //check if paremeters are valid
77  bool invalid=false;
78  for (int i=0;i<3 && !invalid ;i++)
79  {
80  invalid |= std::isnan(Tvec.at<float>(i,0));
81  invalid |= std::isnan(Rvec.at<float>(i,0));
82  }
83  if (invalid) throw cv::Exception(9003,"extrinsic parameters are not set","Marker::getModelViewMatrix",__FILE__,__LINE__);
84  Mat Rot(3,3,CV_32FC1),Jacob;
85  Rodrigues(Rvec, Rot, Jacob);
86 
87  double para[3][4];
88  for (int i=0;i<3;i++)
89  for (int j=0;j<3;j++) para[i][j]=Rot.at<float>(i,j);
90  //now, add the translation
91  para[0][3]=Tvec.at<float>(0,0);
92  para[1][3]=Tvec.at<float>(1,0);
93  para[2][3]=Tvec.at<float>(2,0);
94  double scale=1;
95 
96  modelview_matrix[0 + 0*4] = para[0][0];
97  // R1C2
98  modelview_matrix[0 + 1*4] = para[0][1];
99  modelview_matrix[0 + 2*4] = para[0][2];
100  modelview_matrix[0 + 3*4] = para[0][3];
101  // R2
102  modelview_matrix[1 + 0*4] = para[1][0];
103  modelview_matrix[1 + 1*4] = para[1][1];
104  modelview_matrix[1 + 2*4] = para[1][2];
105  modelview_matrix[1 + 3*4] = para[1][3];
106  // R3
107  modelview_matrix[2 + 0*4] = -para[2][0];
108  modelview_matrix[2 + 1*4] = -para[2][1];
109  modelview_matrix[2 + 2*4] = -para[2][2];
110  modelview_matrix[2 + 3*4] = -para[2][3];
111  modelview_matrix[3 + 0*4] = 0.0;
112  modelview_matrix[3 + 1*4] = 0.0;
113  modelview_matrix[3 + 2*4] = 0.0;
114  modelview_matrix[3 + 3*4] = 1.0;
115  if (scale > 0.0)
116  {
117  modelview_matrix[12] *= scale;
118  modelview_matrix[13] *= scale;
119  modelview_matrix[14] *= scale;
120  }
121  }
122 
123 
124 
125  /****
126  *
127  */
128  void Marker::OgreGetPoseParameters(double position[3], double orientation[4]) throw(cv::Exception)
129  {
130  //check if paremeters are valid
131  bool invalid=false;
132  for (int i=0;i<3 && !invalid ;i++)
133  {
134  invalid |= std::isnan(Tvec.at<float>(i,0));
135  invalid |= std::isnan(Rvec.at<float>(i,0));
136  }
137  if (invalid) throw cv::Exception(9003,"extrinsic parameters are not set","Marker::getModelViewMatrix",__FILE__,__LINE__);
138 
139  // calculate position vector
140  position[0] = Tvec.ptr<float>(0)[0];
141  position[1] = Tvec.ptr<float>(0)[1];
142  position[2] = +Tvec.ptr<float>(0)[2];
143 
144  // now calculare orientation quaternion
145  cv::Mat Rot(3,3,CV_32FC1);
146  cv::Rodrigues(Rvec, Rot);
147 
148  // calculate axes for quaternion
149  double stAxes[3][3];
150  // x axis
151  stAxes[0][0] = -Rot.at<float>(0,0);
152  stAxes[0][1] = -Rot.at<float>(1,0);
153  stAxes[0][2] = +Rot.at<float>(2,0);
154  // y axis
155  stAxes[1][0] = -Rot.at<float>(0,1);
156  stAxes[1][1] = -Rot.at<float>(1,1);
157  stAxes[1][2] = +Rot.at<float>(2,1);
158  // for z axis, we use cross product
159  stAxes[2][0] = stAxes[0][1]*stAxes[1][2] - stAxes[0][2]*stAxes[1][1];
160  stAxes[2][1] = - stAxes[0][0]*stAxes[1][2] + stAxes[0][2]*stAxes[1][0];
161  stAxes[2][2] = stAxes[0][0]*stAxes[1][1] - stAxes[0][1]*stAxes[1][0];
162 
163  // transposed matrix
164  double axes[3][3];
165  axes[0][0] = stAxes[0][0];
166  axes[1][0] = stAxes[0][1];
167  axes[2][0] = stAxes[0][2];
168 
169  axes[0][1] = stAxes[1][0];
170  axes[1][1] = stAxes[1][1];
171  axes[2][1] = stAxes[1][2];
172 
173  axes[0][2] = stAxes[2][0];
174  axes[1][2] = stAxes[2][1];
175  axes[2][2] = stAxes[2][2];
176 
177  // Algorithm in Ken Shoemake's article in 1987 SIGGRAPH course notes
178  // article "Quaternion Calculus and Fast Animation".
179  double fTrace = axes[0][0]+axes[1][1]+axes[2][2];
180  double fRoot;
181 
182  if ( fTrace > 0.0 )
183  {
184  // |w| > 1/2, may as well choose w > 1/2
185  fRoot = sqrt(fTrace + 1.0); // 2w
186  orientation[0] = 0.5*fRoot;
187  fRoot = 0.5/fRoot; // 1/(4w)
188  orientation[1] = (axes[2][1]-axes[1][2])*fRoot;
189  orientation[2] = (axes[0][2]-axes[2][0])*fRoot;
190  orientation[3] = (axes[1][0]-axes[0][1])*fRoot;
191  }
192  else
193  {
194  // |w| <= 1/2
195  static unsigned int s_iNext[3] = { 1, 2, 0 };
196  unsigned int i = 0;
197  if ( axes[1][1] > axes[0][0] )
198  i = 1;
199  if ( axes[2][2] > axes[i][i] )
200  i = 2;
201  unsigned int j = s_iNext[i];
202  unsigned int k = s_iNext[j];
203 
204  fRoot = sqrt(axes[i][i]-axes[j][j]-axes[k][k] + 1.0);
205  double* apkQuat[3] = { &orientation[1], &orientation[2], &orientation[3] };
206  *apkQuat[i] = 0.5*fRoot;
207  fRoot = 0.5/fRoot;
208  orientation[0] = (axes[k][j]-axes[j][k])*fRoot;
209  *apkQuat[j] = (axes[j][i]+axes[i][j])*fRoot;
210  *apkQuat[k] = (axes[k][i]+axes[i][k])*fRoot;
211  }
212  }
213 
214 
215 
216  void Marker::draw(Mat &in, Scalar color, int lineWidth ,bool writeId)const
217  {
218  if (size()!=4) return;
219  cv::line( in,(*this)[0],(*this)[1],color,lineWidth,CV_AA);
220  cv::line( in,(*this)[1],(*this)[2],color,lineWidth,CV_AA);
221  cv::line( in,(*this)[2],(*this)[3],color,lineWidth,CV_AA);
222  cv::line( in,(*this)[3],(*this)[0],color,lineWidth,CV_AA);
223  cv::rectangle( in,(*this)[0]-Point2f(2,2),(*this)[0]+Point2f(2,2),Scalar(0,0,255,255),lineWidth,CV_AA);
224  cv::rectangle( in,(*this)[1]-Point2f(2,2),(*this)[1]+Point2f(2,2),Scalar(0,255,0,255),lineWidth,CV_AA);
225  cv::rectangle( in,(*this)[2]-Point2f(2,2),(*this)[2]+Point2f(2,2),Scalar(255,0,0,255),lineWidth,CV_AA);
226  if (writeId) {
227  char cad[100];
228  sprintf(cad,"id=%d",id);
229  //determine the centroid
230  Point cent(0,0);
231  for (int i=0;i<4;i++)
232  {
233  cent.x+=(*this)[i].x;
234  cent.y+=(*this)[i].y;
235  }
236  cent.x/=4.;
237  cent.y/=4.;
238  putText(in,cad, cent,FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255-color[0],255-color[1],255-color[2],255),2);
239  }
240  }
241 
242  void Marker::calculateExtrinsics(float markerSize,const CameraParameters &CP,bool setYPerpendicular)throw(cv::Exception)
243  {
244  if (!CP.isValid()) throw cv::Exception(9004,"!CP.isValid(): invalid camera parameters. It is not possible to calculate extrinsics","calculateExtrinsics",__FILE__,__LINE__);
245  calculateExtrinsics( markerSize,CP.CameraMatrix,CP.Distorsion,setYPerpendicular);
246  }
247 
248  void print(cv::Point3f p,string cad)
249  {
250  cout<<cad<<" "<<p.x<<" "<<p.y<< " "<<p.z<<endl;
251  }
252 
253  void Marker::calculateExtrinsics(float markerSizeMeters, cv::Mat camMatrix, cv::Mat distCoeff , bool setYPerpendicular)throw(cv::Exception)
254  {
255  if (!isValid()) throw cv::Exception(9004,"!isValid(): invalid marker. It is not possible to calculate extrinsics","calculateExtrinsics",__FILE__,__LINE__);
256  if (markerSizeMeters<=0)throw cv::Exception(9004,"markerSize<=0: invalid markerSize","calculateExtrinsics",__FILE__,__LINE__);
257  if ( camMatrix.rows==0 || camMatrix.cols==0) throw cv::Exception(9004,"CameraMatrix is empty","calculateExtrinsics",__FILE__,__LINE__);
258 
259  double halfSize=markerSizeMeters/2.;
260  cv::Mat ObjPoints(4,3,CV_32FC1);
261  ObjPoints.at<float>(1,0)=-halfSize;
262  ObjPoints.at<float>(1,1)=halfSize;
263  ObjPoints.at<float>(1,2)=0;
264  ObjPoints.at<float>(2,0)=halfSize;
265  ObjPoints.at<float>(2,1)=halfSize;
266  ObjPoints.at<float>(2,2)=0;
267  ObjPoints.at<float>(3,0)=halfSize;
268  ObjPoints.at<float>(3,1)=-halfSize;
269  ObjPoints.at<float>(3,2)=0;
270  ObjPoints.at<float>(0,0)=-halfSize;
271  ObjPoints.at<float>(0,1)=-halfSize;
272  ObjPoints.at<float>(0,2)=0;
273 
274  cv::Mat ImagePoints(4,2,CV_32FC1);
275 
276  //Set image points from the marker
277  for (int c=0;c<4;c++)
278  {
279  ImagePoints.at<float>(c,0)=((*this)[c%4].x);
280  ImagePoints.at<float>(c,1)=((*this)[c%4].y);
281  }
282 
283  cv::Mat raux,taux;
284  cv::solvePnP(ObjPoints, ImagePoints, camMatrix, distCoeff,raux,taux);
285  raux.convertTo(Rvec,CV_32F);
286  taux.convertTo(Tvec ,CV_32F);
287  //rotate the X axis so that Y is perpendicular to the marker plane
288  if (setYPerpendicular) rotateXAxis(Rvec);
289  ssize=markerSizeMeters;
290  }
291 
292  void Marker::rotateXAxis(Mat &rotation)
293  {
294  cv::Mat R(3,3,CV_32F);
295  cv::Rodrigues(rotation, R);
296  //create a rotation matrix for x axis
297  cv::Mat RX=cv::Mat::eye(3,3,CV_32F);
298  float angleRad=M_PI/2;
299  RX.at<float>(1,1)=cos(angleRad);
300  RX.at<float>(1,2)=-sin(angleRad);
301  RX.at<float>(2,1)=sin(angleRad);
302  RX.at<float>(2,2)=cos(angleRad);
303  //now multiply
304  R=R*RX;
305  //finally, the the rodrigues back
306  cv::Rodrigues(R,rotation);
307  }
308 
309  cv::Point2f Marker::getCenter()const
310  {
311  cv::Point2f cent(0,0);
312  for(size_t i=0;i<size();i++){
313  cent.x+=(*this)[i].x;
314  cent.y+=(*this)[i].y;
315  }
316  cent.x/=float(size());
317  cent.y/=float(size());
318  return cent;
319  }
320 
321  float Marker::getArea()const
322  {
323  assert(size()==4);
324  //use the cross products
325  cv::Point2f v01=(*this)[1]-(*this)[0];
326  cv::Point2f v03=(*this)[3]-(*this)[0];
327  float area1=fabs(v01.x*v03.y - v01.y*v03.x);
328  cv::Point2f v21=(*this)[1]-(*this)[2];
329  cv::Point2f v23=(*this)[3]-(*this)[2];
330  float area2=fabs(v21.x*v23.y - v21.y*v23.x);
331  return (area2+area1)/2.;
332  }
333 
334  float Marker::getPerimeter()const
335  {
336  assert(size()==4);
337  float sum=0;
338  for(int i=0;i<4;i++)
339  sum+=norm( (*this)[i]-(*this)[(i+1)%4]);
340  return sum;
341  }
342 
343 }
void rotateXAxis(cv::Mat &rotation)
Definition: marker.cpp:292
bool isValid() const
Definition: marker.h:65
cv::Mat Rvec
Definition: marker.h:49
void calculateExtrinsics(float markerSize, const CameraParameters &CP, bool setYPerpendicular=true)
Definition: marker.cpp:242
float getArea() const
Definition: marker.cpp:321
This class represents a marker. It is a vector of the fours corners ot the marker.
Definition: marker.h:41
Parameters of the camera.
float ssize
Definition: marker.h:47
void glGetModelViewMatrix(double modelview_matrix[16])
Definition: marker.cpp:74
cv::Point2f getCenter() const
Definition: marker.cpp:309
cv::Mat Tvec
Definition: marker.h:49
void draw(cv::Mat &in, cv::Scalar color, int lineWidth=1, bool writeId=true) const
Definition: marker.cpp:216
void print(cv::Point3f p, string cad)
Definition: marker.cpp:248
float getPerimeter() const
Definition: marker.cpp:334
void OgreGetPoseParameters(double position[3], double orientation[4])
Definition: marker.cpp:128


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Wed Sep 2 2020 04:02:09