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 "marker.h"
29 #define _USE_MATH_DEFINES
30 #include <math.h>
31 #include <cstdio>
32 #include <opencv2/calib3d/calib3d.hpp>
33 #include <opencv2/highgui/highgui.hpp>
34 #include <opencv2/imgproc/imgproc.hpp>
35 using namespace cv;
36 namespace aruco {
40 Marker::Marker() {
41  id = -1;
42  ssize = -1;
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;
47 }
51 Marker::Marker(int _id) {
52  id = _id;
53  ssize = -1;
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;
58 }
62 Marker::Marker(const Marker &M) : std::vector< cv::Point2f >(M) {
63  M.Rvec.copyTo(Rvec);
64  M.Tvec.copyTo(Tvec);
65  id = M.id;
66  ssize = M.ssize;
67 }
68 
72 Marker::Marker(const std::vector< cv::Point2f > &corners, int _id) : std::vector< cv::Point2f >(corners) {
73  id = _id;
74  ssize = -1;
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;
79 }
80 
84 void Marker::glGetModelViewMatrix(double modelview_matrix[16]) throw(cv::Exception) {
85  // check if paremeters are valid
86  bool invalid = false;
87  for (int i = 0; i < 3 && !invalid; i++) {
88  if (Tvec.at< float >(i, 0) != -999999)
89  invalid |= false;
90  if (Rvec.at< float >(i, 0) != -999999)
91  invalid |= false;
92  }
93  if (invalid)
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);
97 
98  double para[3][4];
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);
102  // now, add the translation
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);
106  double scale = 1;
107 
108  modelview_matrix[0 + 0 * 4] = para[0][0];
109  // R1C2
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];
113  // R2
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];
118  // R3
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;
127  if (scale != 0.0) {
128  modelview_matrix[12] *= scale;
129  modelview_matrix[13] *= scale;
130  modelview_matrix[14] *= scale;
131  }
132 }
133 
134 
135 
136 /****
137  *
138  */
139 void Marker::OgreGetPoseParameters(double position[3], double orientation[4]) throw(cv::Exception) {
140 
141  // check if paremeters are valid
142  bool invalid = false;
143  for (int i = 0; i < 3 && !invalid; i++) {
144  if (Tvec.at< float >(i, 0) != -999999)
145  invalid |= false;
146  if (Rvec.at< float >(i, 0) != -999999)
147  invalid |= false;
148  }
149  if (invalid)
150  throw cv::Exception(9003, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
151 
152  // calculate position vector
153  position[0] = -Tvec.ptr< float >(0)[0];
154  position[1] = -Tvec.ptr< float >(0)[1];
155  position[2] = +Tvec.ptr< float >(0)[2];
156 
157  // now calculare orientation quaternion
158  cv::Mat Rot(3, 3, CV_32FC1);
159  cv::Rodrigues(Rvec, Rot);
160 
161  // calculate axes for quaternion
162  double stAxes[3][3];
163  // x axis
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);
167  // y axis
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);
171  // for z axis, we use cross product
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];
175 
176  // transposed matrix
177  double axes[3][3];
178  axes[0][0] = stAxes[0][0];
179  axes[1][0] = stAxes[0][1];
180  axes[2][0] = stAxes[0][2];
181 
182  axes[0][1] = stAxes[1][0];
183  axes[1][1] = stAxes[1][1];
184  axes[2][1] = stAxes[1][2];
185 
186  axes[0][2] = stAxes[2][0];
187  axes[1][2] = stAxes[2][1];
188  axes[2][2] = stAxes[2][2];
189 
190  // Algorithm in Ken Shoemake's article in 1987 SIGGRAPH course notes
191  // article "Quaternion Calculus and Fast Animation".
192  double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
193  double fRoot;
194 
195  if (fTrace > 0.0) {
196  // |w| > 1/2, may as well choose w > 1/2
197  fRoot = sqrt(fTrace + 1.0); // 2w
198  orientation[0] = 0.5 * fRoot;
199  fRoot = 0.5 / fRoot; // 1/(4w)
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;
203  } else {
204  // |w| <= 1/2
205  static unsigned int s_iNext[3] = {1, 2, 0};
206  unsigned int i = 0;
207  if (axes[1][1] > axes[0][0])
208  i = 1;
209  if (axes[2][2] > axes[i][i])
210  i = 2;
211  unsigned int j = s_iNext[i];
212  unsigned int k = s_iNext[j];
213 
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;
217  fRoot = 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;
221  }
222 }
223 
224 
225 
226 void Marker::draw(Mat &in, Scalar color, int lineWidth, bool writeId) const {
227  if (size() != 4)
228  return;
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);
236  if (writeId) {
237  char cad[100];
238  sprintf(cad, "id=%d", id);
239  // determine the centroid
240  Point cent(0, 0);
241  for (int i = 0; i < 4; i++) {
242  cent.x += (*this)[i].x;
243  cent.y += (*this)[i].y;
244  }
245  cent.x /= 4.;
246  cent.y /= 4.;
247  putText(in, cad, cent, FONT_HERSHEY_SIMPLEX, 0.5, Scalar(255 - color[0], 255 - color[1], 255 - color[2], 255), 2);
248  }
249 }
250 
253 void Marker::calculateExtrinsics(float markerSize, const CameraParameters &CP, bool setYPerpendicular) throw(cv::Exception) {
254  if (!CP.isValid())
255  throw cv::Exception(9004, "!CP.isValid(): invalid camera parameters. It is not possible to calculate extrinsics", "calculateExtrinsics", __FILE__,
256  __LINE__);
257  calculateExtrinsics(markerSize, CP.CameraMatrix, CP.Distorsion, setYPerpendicular);
258 }
259 
260 void print(cv::Point3f p, string cad) { cout << cad << " " << p.x << " " << p.y << " " << p.z << endl; }
263 void Marker::calculateExtrinsics(float markerSizeMeters, cv::Mat camMatrix, cv::Mat distCoeff, bool setYPerpendicular) throw(cv::Exception) {
264  if (!isValid())
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__);
270 
271  vector<cv::Point3f> objpoints=get3DPoints(markerSizeMeters);
272 
273 
274 
275  cv::Mat raux, taux;
276  cv::solvePnP(objpoints, *this, camMatrix, distCoeff, raux, taux);
277  raux.convertTo(Rvec, CV_32F);
278  taux.convertTo(Tvec, CV_32F);
279  // rotate the X axis so that Y is perpendicular to the marker plane
280  if (setYPerpendicular)
281  rotateXAxis(Rvec);
282  ssize = markerSizeMeters;
283  // cout<<(*this)<<endl;
284 }
285 vector<cv::Point3f> Marker::get3DPoints(float msize)
286 {
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)};
289 
290 }
291 
295 void Marker::rotateXAxis(Mat &rotation) {
296  cv::Mat R(3, 3, CV_32F);
297  Rodrigues(rotation, R);
298  // create a rotation matrix for x axis
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);
305  // now multiply
306  R = R * RX;
307  // finally, the the rodrigues back
308  Rodrigues(R, rotation);
309 }
310 
311 
312 
315 cv::Point2f Marker::getCenter() const {
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;
320  }
321  cent.x /= float(size());
322  cent.y /= float(size());
323  return cent;
324 }
325 
328 float Marker::getArea() const {
329  assert(size() == 4);
330  // use the cross products
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.;
338 }
341 float Marker::getPerimeter() const {
342  assert(size() == 4);
343  float sum = 0;
344  for (int i = 0; i < 4; i++)
345  sum += norm((*this)[i] - (*this)[(i + 1) % 4]);
346  return sum;
347 }
348 //saves to a binary stream
349 void Marker::toStream(ostream &str)const{
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));
355  //write the 2d points
356  uint32_t np=size();
357  str.write((char*) &np, sizeof(np));
358  for(size_t i=0;i<size();i++) str.write((char*) &at(i), sizeof(cv::Point2f));
359 
360 }
361 //reads from a binary stream
362 void Marker::fromStream(istream &str){
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));
369  uint32_t np;
370  str.read((char*) &np, sizeof(np));
371  resize(np);
372  for(size_t i=0;i<size();i++) str.read((char*) &(*this)[i], sizeof(cv::Point2f));
373 
374 }
375 
376 }
std::vector< cv::Mat > solvePnP(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
Definition: ippe.cpp:55
void toStream(ostream &str) const
Definition: marker.cpp:349
static vector< cv::Point3f > get3DPoints(float msize)
Definition: marker.cpp:285
void rotateXAxis(cv::Mat &rotation)
Definition: marker.cpp:295
bool isValid() const
Definition: marker.h:68
cv::Mat Rvec
Definition: marker.h:49
TFSIMD_FORCE_INLINE const tfScalar & x() const
void calculateExtrinsics(float markerSize, const CameraParameters &CP, bool setYPerpendicular=true)
Definition: marker.cpp:253
float getArea() const
Definition: marker.cpp:328
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.
Definition: marker.h:42
Parameters of the camera.
float ssize
Definition: marker.h:47
void glGetModelViewMatrix(double modelview_matrix[16])
Definition: marker.cpp:84
cv::Point2f getCenter() const
Definition: marker.cpp:315
cv::Mat Tvec
Definition: marker.h:49
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
Definition: marker.cpp:226
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const
void print(cv::Point3f p, string cad)
Definition: marker.cpp:260
float getPerimeter() const
Definition: marker.cpp:341
void OgreGetPoseParameters(double position[3], double orientation[4])
Definition: marker.cpp:139
void fromStream(istream &str)
Definition: marker.cpp:362


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:40:53