markermap.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 "markermap.h"
29 #include <opencv2/calib3d/calib3d.hpp>
30 #include <opencv2/imgproc/imgproc.hpp>
31 #include <opencv2/highgui/highgui.hpp>
32 
33 #include <fstream>
34 #include "dictionary.h"
35 using namespace std;
36 using namespace cv;
37 namespace aruco {
38 
43 MarkerMap::MarkerMap() { mInfoType = NONE; }
48 MarkerMap::MarkerMap(string filePath) throw(cv::Exception) {
49  mInfoType = NONE;
50  readFromFile(filePath);
51 }
52 
53 
58 void MarkerMap::saveToFile(string sfile) throw(cv::Exception) {
59 
60  cv::FileStorage fs(sfile, cv::FileStorage::WRITE);
61  saveToFile(fs);
62 }
65 void MarkerMap::saveToFile(cv::FileStorage &fs) throw(cv::Exception) {
66  fs<<"aruco_bc_dict"<<dictionary;
67  fs << "aruco_bc_nmarkers" << (int)size();
68  fs << "aruco_bc_mInfoType" << (int)mInfoType;
69  fs << "aruco_bc_markers"
70  << "[";
71  for (size_t i = 0; i < size(); i++) {
72  fs << "{:"
73  << "id" << at(i).id;
74 
75  fs << "corners"
76  << "[:";
77  for (size_t c = 0; c < at(i).size(); c++)
78  fs << at(i)[c];
79  fs << "]";
80  fs << "}";
81  }
82  fs << "]";
83 }
84 
89 void MarkerMap::readFromFile(string sfile) throw(cv::Exception) {
90  try {
91  cv::FileStorage fs(sfile, cv::FileStorage::READ);
92  readFromFile(fs);
93  } catch (std::exception &ex) {
94  throw cv::Exception(81818, "MarkerMap::readFromFile", ex.what() + string(" file=)") + sfile, __FILE__, __LINE__);
95  }
96 }
97 
98 
101 void MarkerMap::readFromFile(cv::FileStorage &fs) throw(cv::Exception) {
102  int aux = 0;
103  // look for the nmarkers
104  if (fs["aruco_bc_nmarkers"].name() != "aruco_bc_nmarkers")
105  throw cv::Exception(81818, "MarkerMap::readFromFile", "invalid file type", __FILE__, __LINE__);
106  fs["aruco_bc_nmarkers"] >> aux;
107  resize(aux);
108  fs["aruco_bc_mInfoType"] >> mInfoType;
109  cv::FileNode markers = fs["aruco_bc_markers"];
110  int i = 0;
111  for (FileNodeIterator it = markers.begin(); it != markers.end(); ++it, i++) {
112  at(i).id = (*it)["id"];
113  FileNode FnCorners = (*it)["corners"];
114  for (FileNodeIterator itc = FnCorners.begin(); itc != FnCorners.end(); ++itc) {
115  vector< float > coordinates3d;
116  (*itc) >> coordinates3d;
117  if (coordinates3d.size() != 3)
118  throw cv::Exception(81818, "MarkerMap::readFromFile", "invalid file type 3", __FILE__, __LINE__);
119  cv::Point3f point(coordinates3d[0], coordinates3d[1], coordinates3d[2]);
120  at(i).push_back(point);
121  }
122  }
123 
124  if (fs["aruco_bc_dict"].name()=="aruco_bc_dict")
125  fs["aruco_bc_dict"] >> dictionary;
126 
127 }
128 
131 int MarkerMap::getIndexOfMarkerId(int id) const {
132 
133  for (size_t i = 0; i < size(); i++)
134  if (at(i).id == id)
135  return i;
136  return -1;
137 }
138 
141 const Marker3DInfo &MarkerMap::getMarker3DInfo(int id) const throw(cv::Exception) {
142  for (size_t i = 0; i < size(); i++)
143  if (at(i).id == id)
144  return at(i);
145  throw cv::Exception(111, "MarkerMap::getMarker3DInfo", "Marker with the id given is not found", __FILE__, __LINE__);
146 }
147 
148 
149 void __glGetModelViewMatrix(double modelview_matrix[16],const cv::Mat &Rvec,const cv::Mat &Tvec) throw(cv::Exception) {
150  // check if paremeters are valid
151  bool invalid = false;
152  for (int i = 0; i < 3 && !invalid; i++) {
153  if (Tvec.at< float >(i, 0) != -999999)
154  invalid |= false;
155  if (Rvec.at< float >(i, 0) != -999999)
156  invalid |= false;
157  }
158  if (invalid)
159  throw cv::Exception(9002, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
160  Mat Rot(3, 3, CV_32FC1), Jacob;
161  Rodrigues(Rvec, Rot, Jacob);
162 
163  double para[3][4];
164  for (int i = 0; i < 3; i++)
165  for (int j = 0; j < 3; j++)
166  para[i][j] = Rot.at< float >(i, j);
167  // now, add the translation
168  para[0][3] = Tvec.at< float >(0, 0);
169  para[1][3] = Tvec.at< float >(1, 0);
170  para[2][3] = Tvec.at< float >(2, 0);
171  double scale = 1;
172 
173  modelview_matrix[0 + 0 * 4] = para[0][0];
174  // R1C2
175  modelview_matrix[0 + 1 * 4] = para[0][1];
176  modelview_matrix[0 + 2 * 4] = para[0][2];
177  modelview_matrix[0 + 3 * 4] = para[0][3];
178  // R2
179  modelview_matrix[1 + 0 * 4] = para[1][0];
180  modelview_matrix[1 + 1 * 4] = para[1][1];
181  modelview_matrix[1 + 2 * 4] = para[1][2];
182  modelview_matrix[1 + 3 * 4] = para[1][3];
183  // R3
184  modelview_matrix[2 + 0 * 4] = -para[2][0];
185  modelview_matrix[2 + 1 * 4] = -para[2][1];
186  modelview_matrix[2 + 2 * 4] = -para[2][2];
187  modelview_matrix[2 + 3 * 4] = -para[2][3];
188  modelview_matrix[3 + 0 * 4] = 0.0;
189  modelview_matrix[3 + 1 * 4] = 0.0;
190  modelview_matrix[3 + 2 * 4] = 0.0;
191  modelview_matrix[3 + 3 * 4] = 1.0;
192  if (scale != 0.0) {
193  modelview_matrix[12] *= scale;
194  modelview_matrix[13] *= scale;
195  modelview_matrix[14] *= scale;
196  }
197 }
198 
199 
200 /****
201  *
202  */
203 void __OgreGetPoseParameters(double position[3], double orientation[4],const cv::Mat &Rvec,const cv::Mat &Tvec) throw(cv::Exception) {
204  // check if paremeters are valid
205  bool invalid = false;
206  for (int i = 0; i < 3 && !invalid; i++) {
207  if (Tvec.at< float >(i, 0) != -999999)
208  invalid |= false;
209  if (Rvec.at< float >(i, 0) != -999999)
210  invalid |= false;
211  }
212  if (invalid)
213  throw cv::Exception(9003, "extrinsic parameters are not set", "Marker::getModelViewMatrix", __FILE__, __LINE__);
214 
215  // calculate position vector
216  position[0] = -Tvec.ptr< float >(0)[0];
217  position[1] = -Tvec.ptr< float >(0)[1];
218  position[2] = +Tvec.ptr< float >(0)[2];
219 
220  // now calculare orientation quaternion
221  cv::Mat Rot(3, 3, CV_32FC1);
222  cv::Rodrigues(Rvec, Rot);
223 
224  // calculate axes for quaternion
225  double stAxes[3][3];
226  // x axis
227  stAxes[0][0] = -Rot.at< float >(0, 0);
228  stAxes[0][1] = -Rot.at< float >(1, 0);
229  stAxes[0][2] = +Rot.at< float >(2, 0);
230  // y axis
231  stAxes[1][0] = -Rot.at< float >(0, 1);
232  stAxes[1][1] = -Rot.at< float >(1, 1);
233  stAxes[1][2] = +Rot.at< float >(2, 1);
234  // for z axis, we use cross product
235  stAxes[2][0] = stAxes[0][1] * stAxes[1][2] - stAxes[0][2] * stAxes[1][1];
236  stAxes[2][1] = -stAxes[0][0] * stAxes[1][2] + stAxes[0][2] * stAxes[1][0];
237  stAxes[2][2] = stAxes[0][0] * stAxes[1][1] - stAxes[0][1] * stAxes[1][0];
238 
239  // transposed matrix
240  double axes[3][3];
241  axes[0][0] = stAxes[0][0];
242  axes[1][0] = stAxes[0][1];
243  axes[2][0] = stAxes[0][2];
244 
245  axes[0][1] = stAxes[1][0];
246  axes[1][1] = stAxes[1][1];
247  axes[2][1] = stAxes[1][2];
248 
249  axes[0][2] = stAxes[2][0];
250  axes[1][2] = stAxes[2][1];
251  axes[2][2] = stAxes[2][2];
252 
253  // Algorithm in Ken Shoemake's article in 1987 SIGGRAPH course notes
254  // article "Quaternion Calculus and Fast Animation".
255  double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
256  double fRoot;
257 
258  if (fTrace > 0.0) {
259  // |w| > 1/2, may as well choose w > 1/2
260  fRoot = sqrt(fTrace + 1.0); // 2w
261  orientation[0] = 0.5 * fRoot;
262  fRoot = 0.5 / fRoot; // 1/(4w)
263  orientation[1] = (axes[2][1] - axes[1][2]) * fRoot;
264  orientation[2] = (axes[0][2] - axes[2][0]) * fRoot;
265  orientation[3] = (axes[1][0] - axes[0][1]) * fRoot;
266  } else {
267  // |w| <= 1/2
268  static unsigned int s_iNext[3] = {1, 2, 0};
269  unsigned int i = 0;
270  if (axes[1][1] > axes[0][0])
271  i = 1;
272  if (axes[2][2] > axes[i][i])
273  i = 2;
274  unsigned int j = s_iNext[i];
275  unsigned int k = s_iNext[j];
276 
277  fRoot = sqrt(axes[i][i] - axes[j][j] - axes[k][k] + 1.0);
278  double *apkQuat[3] = {&orientation[1], &orientation[2], &orientation[3]};
279  *apkQuat[i] = 0.5 * fRoot;
280  fRoot = 0.5 / fRoot;
281  orientation[0] = (axes[k][j] - axes[j][k]) * fRoot;
282  *apkQuat[j] = (axes[j][i] + axes[i][j]) * fRoot;
283  *apkQuat[k] = (axes[k][i] + axes[i][k]) * fRoot;
284  }
285 }
286 
287 
290 void MarkerMap::getIdList(std::vector< int > &ids, bool append) const {
291  if (!append)
292  ids.clear();
293  for (size_t i = 0; i < size(); i++)
294  ids.push_back(at(i).id);
295 }
296 
297 MarkerMap MarkerMap::convertToMeters(float markerSize_meters)throw (cv::Exception){
298 
299  if (!isExpressedInPixels())
300  throw cv::Exception(-1,"The board is not expressed in pixels", "MarkerMap::convertToMeters", __FILE__, __LINE__);
301  // first, we are assuming all markers are equally sized. So, lets get the size in pixels
302  int markerSizePix = cv::norm(at(0)[0] - at(0)[1]);
303  MarkerMap BInfo(*this);
304  BInfo.mInfoType = MarkerMap::METERS;
305  // now, get the size of a pixel, and change scale
306  float pixSize = markerSize_meters / float(markerSizePix);
307  cout << markerSize_meters << " " << float(markerSizePix) << " " << pixSize << endl;
308  for (size_t i = 0; i < BInfo.size(); i++)
309  for (int c = 0; c < 4; c++) {
310  BInfo[i][c] *= pixSize;
311  }
312  return BInfo;
313 }
314 cv::Mat MarkerMap::getImage(float METER2PIX)const throw (cv::Exception){
315 
316  if (mInfoType==NONE)
317  throw cv::Exception(-1,"The board is not valid mInfoType==NONE ", "MarkerMap::getImage", __FILE__, __LINE__);
318  if (METER2PIX<=0 && mInfoType!=PIX)
319  throw cv::Exception(-1,"The board is not expressed in pixels and not METER2PIX indicated", "MarkerMap::getImage", __FILE__, __LINE__);
320 
321  auto Dict=Dictionary::loadPredefined(dictionary);
322 
323  //get image limits
324  cv::Point pmin(std::numeric_limits<int>::max(),std::numeric_limits<int>::max()),pmax(std::numeric_limits<int>::lowest(),std::numeric_limits<int>::lowest());
325  for(auto b:*this){
326  for(auto p:b){
327  pmin.x=min(int(p.x),pmin.x);
328  pmin.y=min(int(p.y),pmin.y);
329  pmax.x=max(int(p.x+0.5),pmax.x);
330  pmax.y=max(int(p.y+0.5),pmax.y);
331  assert(p.z==0);
332  }
333  }
334 
335  cv::Point psize=pmax-pmin;
336  cv::Mat image(cv::Size( psize.x,psize.y),CV_8UC1);
337  image.setTo(cv::Scalar::all(255));
338 
339  vector<Marker3DInfo> p3d=*this;
340  //the points must be moved from a real reference system to image reference sysmte (y positive is inverse)
341  for(auto &m:p3d)
342  for(auto &p:m){
343  p-=cv::Point3f(pmin.x,pmax.y,0);
344  //now, use inverse y
345  p.y=-p.y;
346  }
347  for(auto m:p3d)
348  {
349  //get size and find size of this
350  float size=cv::norm( m[0]-m[1]);
351  auto im1=Dict.getMarkerImage_id(m.id,int(size/8));
352  cv::Mat im2;
353  //now resize to fit
354  cv::resize(im1,im2,cv::Size(size,size));
355  //copy in correct position
356  auto ry=cv::Range(int(m[0].y),int(m[2].y) ) ;
357  auto rx=cv::Range(int(m[0].x),int(m[2].x));
358  cv::Mat sub=image(ry,rx);
359  im2.copyTo(sub);
360  }
361  return image;
362 }
363 
364 std::vector<int> MarkerMap::getIndices(vector<aruco::Marker> &markers)
365 {
366  std::vector<int> indices;
367  for(size_t i=0;i<markers.size();i++){
368  bool found=false;
369  for(size_t j=0;j<size() &&!found;j++){
370  if (markers[i].id==at(j).id){
371  found=true;
372  indices.push_back(i);
373  }
374  }
375  }
376  return indices;
377 }
378 void MarkerMap::toStream(std::ostream &str){
379  str<<mInfoType<<" " <<size()<<" ";
380  for(size_t i=0;i<size();i++) {at(i).toStream(str); }
381  //write dic string info
382  str<<dictionary;
383 }
384 void MarkerMap::fromStream(std::istream &str){
385  int s; str>>mInfoType>>s;resize(s);
386  for(size_t i=0;i<size();i++) at(i).fromStream(str);
387  str>>dictionary;
388 }
389 pair<cv::Mat,cv::Mat> MarkerMap::calculateExtrinsics(const std::vector<aruco::Marker> &markers ,float markerSize, cv::Mat CameraMatrix, cv::Mat Distorsion ) throw(cv::Exception){
390  vector<cv::Point2f> p2d;
391  MarkerMap m_meters;
392  if (isExpressedInPixels())
393  m_meters=convertToMeters(markerSize);
394  else m_meters=*this;
395  vector<cv::Point3f> p3d;
396  for(auto marker:markers){
397  auto it=find(m_meters.begin(),m_meters.end(),marker.id);
398  if ( it!=m_meters.end()){//is the marker part of the map?
399  for(auto p:marker) p2d.push_back(p);
400  for(auto p:*it) p3d.push_back(p);
401  }
402  }
403 
404  cv::Mat rvec,tvec;
405  if (p2d.size()!=0)//no points in the vector
406  cv::solvePnPRansac(p3d,p2d,CameraMatrix,Distorsion,rvec,tvec);
407  return make_pair(rvec,tvec);
408 
409 }
410 
411 };
NONE
XmlRpcServer s
void __glGetModelViewMatrix(double modelview_matrix[16], const cv::Mat &Rvec, const cv::Mat &Tvec)
Definition: markermap.cpp:149
Packet pmax(const Packet &a, const Packet &b)
void __OgreGetPoseParameters(double position[3], double orientation[4], const cv::Mat &Rvec, const cv::Mat &Tvec)
Definition: markermap.cpp:203
Packet pmin(const Packet &a, const Packet &b)
TFSIMD_FORCE_INLINE const tfScalar & x() const
int min(int a, int b)
const CwiseUnaryOp< internal::scalar_sqrt_op< Scalar >, const Derived > sqrt() const
This class defines a set of markers whose locations are attached to a common reference system...
Definition: markermap.h:71


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