28 #include <aruco/board.h> 39 BoardConfiguration::BoardConfiguration()
59 vector<MarkerInfo>::operator=(T);
70 cv::FileStorage fs ( sfile,cv::FileStorage::WRITE );
77 fs<<
"aruco_bc_nmarkers"<< ( int ) size();
78 fs<<
"aruco_bc_mInfoType"<< ( int )
mInfoType;
79 fs<<
"aruco_bc_markers"<<
"[";
80 for (
size_t i=0;i<size();i++ )
82 fs <<
"{:" <<
"id" << at(i).id ;
85 for (
size_t c=0;c<at(i).size();++c)
99 cv::FileStorage fs ( sfile,cv::FileStorage::READ );
111 if ( fs[
"aruco_bc_nmarkers"].name() !=
"aruco_bc_nmarkers" )
112 throw cv::Exception ( 81818,
"BoardConfiguration::readFromFile",
"invalid file type" ,__FILE__,__LINE__ );
113 fs[
"aruco_bc_nmarkers"]>>aux;
116 cv::FileNode
markers=fs[
"aruco_bc_markers"];
118 for (FileNodeIterator it = markers.begin();it!=markers.end();++it,i++) {
119 at(i).id=(*it)[
"id"];
120 FileNode FnCorners=(*it)[
"corners"];
121 for (FileNodeIterator itc = FnCorners.begin();itc!=FnCorners.end();++itc) {
122 vector<float> coordinates3d;
123 (*itc)>>coordinates3d;
124 if(coordinates3d.size()!=3)
125 throw cv::Exception ( 81818,
"BoardConfiguration::readFromFile",
"invalid file type 3" ,__FILE__,__LINE__ );
126 cv::Point3f point(coordinates3d[0],coordinates3d[1],coordinates3d[2]);
127 at(i).push_back(point);
137 for(
size_t i=0;i<size();i++)
138 if( at(i).id==id)
return i;
146 for(
size_t i=0;i<size();i++)
147 if( at(i).id ==id)
return at(i);
148 throw cv::Exception(111,
"BoardConfiguration::getMarkerInfo",
"Marker with the id given is not found",__FILE__,__LINE__);
159 for (
int i=0;i<3 && !invalid ;i++ )
161 invalid |= std::isnan(Tvec.at<
float>(i,0));
162 invalid |= std::isnan(Rvec.at<
float>(i,0));
164 if ( invalid )
throw cv::Exception ( 9002,
"extrinsic parameters are not set",
"Marker::getModelViewMatrix",__FILE__,__LINE__ );
165 Mat Rot ( 3,3,CV_32FC1 ),Jacob;
166 Rodrigues ( Rvec, Rot, Jacob );
169 for (
int i=0;i<3;i++ )
170 for (
int j=0;j<3;j++ ) para[i][j]=Rot.at<
float> ( i,j );
172 para[0][3]=Tvec.at<
float> ( 0,0 );
173 para[1][3]=Tvec.at<
float> ( 1,0 );
174 para[2][3]=Tvec.at<
float> ( 2,0 );
177 modelview_matrix[0 + 0*4] = para[0][0];
179 modelview_matrix[0 + 1*4] = para[0][1];
180 modelview_matrix[0 + 2*4] = para[0][2];
181 modelview_matrix[0 + 3*4] = para[0][3];
183 modelview_matrix[1 + 0*4] = para[1][0];
184 modelview_matrix[1 + 1*4] = para[1][1];
185 modelview_matrix[1 + 2*4] = para[1][2];
186 modelview_matrix[1 + 3*4] = para[1][3];
188 modelview_matrix[2 + 0*4] = -para[2][0];
189 modelview_matrix[2 + 1*4] = -para[2][1];
190 modelview_matrix[2 + 2*4] = -para[2][2];
191 modelview_matrix[2 + 3*4] = -para[2][3];
192 modelview_matrix[3 + 0*4] = 0.0;
193 modelview_matrix[3 + 1*4] = 0.0;
194 modelview_matrix[3 + 2*4] = 0.0;
195 modelview_matrix[3 + 3*4] = 1.0;
198 modelview_matrix[12] *= scale;
199 modelview_matrix[13] *= scale;
200 modelview_matrix[14] *= scale;
214 for (
int i=0;i<3 && !invalid ;i++ )
216 invalid |= std::isnan(Tvec.at<
float>(i,0));
217 invalid |= std::isnan(Rvec.at<
float>(i,0));
219 if ( invalid )
throw cv::Exception ( 9003,
"extrinsic parameters are not set",
"Marker::getModelViewMatrix",__FILE__,__LINE__ );
222 position[0] = -Tvec.ptr<
float> ( 0 ) [0];
223 position[1] = -Tvec.ptr<
float> ( 0 ) [1];
224 position[2] = +Tvec.ptr<
float> ( 0 ) [2];
227 cv::Mat Rot ( 3,3,CV_32FC1 );
228 cv::Rodrigues ( Rvec, Rot );
233 stAxes[0][0] = -Rot.at<
float> ( 0,0 );
234 stAxes[0][1] = -Rot.at<
float> ( 1,0 );
235 stAxes[0][2] = +Rot.at<
float> ( 2,0 );
237 stAxes[1][0] = -Rot.at<
float> ( 0,1 );
238 stAxes[1][1] = -Rot.at<
float> ( 1,1 );
239 stAxes[1][2] = +Rot.at<
float> ( 2,1 );
241 stAxes[2][0] = stAxes[0][1]*stAxes[1][2] - stAxes[0][2]*stAxes[1][1];
242 stAxes[2][1] = - stAxes[0][0]*stAxes[1][2] + stAxes[0][2]*stAxes[1][0];
243 stAxes[2][2] = stAxes[0][0]*stAxes[1][1] - stAxes[0][1]*stAxes[1][0];
247 axes[0][0] = stAxes[0][0];
248 axes[1][0] = stAxes[0][1];
249 axes[2][0] = stAxes[0][2];
251 axes[0][1] = stAxes[1][0];
252 axes[1][1] = stAxes[1][1];
253 axes[2][1] = stAxes[1][2];
255 axes[0][2] = stAxes[2][0];
256 axes[1][2] = stAxes[2][1];
257 axes[2][2] = stAxes[2][2];
261 double fTrace = axes[0][0]+axes[1][1]+axes[2][2];
267 fRoot = sqrt ( fTrace + 1.0 );
268 orientation[0] = 0.5*fRoot;
270 orientation[1] = ( axes[2][1]-axes[1][2] ) *fRoot;
271 orientation[2] = ( axes[0][2]-axes[2][0] ) *fRoot;
272 orientation[3] = ( axes[1][0]-axes[0][1] ) *fRoot;
277 static unsigned int s_iNext[3] = { 1, 2, 0 };
279 if ( axes[1][1] > axes[0][0] )
281 if ( axes[2][2] > axes[i][i] )
283 unsigned int j = s_iNext[i];
284 unsigned int k = s_iNext[j];
286 fRoot = sqrt ( axes[i][i]-axes[j][j]-axes[k][k] + 1.0 );
287 double* apkQuat[3] = { &orientation[1], &orientation[2], &orientation[3] };
288 *apkQuat[i] = 0.5*fRoot;
290 orientation[0] = ( axes[k][j]-axes[j][k] ) *fRoot;
291 *apkQuat[j] = ( axes[j][i]+axes[i][j] ) *fRoot;
292 *apkQuat[k] = ( axes[k][i]+axes[i][k] ) *fRoot;
303 cv::FileStorage fs ( filePath,cv::FileStorage::WRITE );
305 fs<<
"aruco_bo_rvec"<< Rvec;
306 fs<<
"aruco_bo_tvec"<< Tvec;
308 fs<<
"aruco_bo_nmarkers"<< ( int ) size();
309 fs<<
"aruco_bo_markers"<<
"[";
310 for (
size_t i=0;i<size();++i )
312 fs <<
"{:" <<
"id" << at(i).id ;
313 fs<<
"corners"<<
"[:";
314 for (
size_t c=0;c<at(i).size();++c)
332 cv::FileStorage fs ( filePath,cv::FileStorage::READ );
333 if ( fs[
"aruco_bo_nmarkers"].name() !=
"aruco_bo_nmarkers" )
334 throw cv::Exception ( 81818,
"Board::readFromFile",
"invalid file type:" ,__FILE__,__LINE__ );
340 fs[
"aruco_bo_nmarkers"]>>aux;
342 fs[
"aruco_bo_rvec"]>> Rvec;
343 fs[
"aruco_bo_tvec"]>> Tvec;
345 cv::FileNode
markers=fs[
"aruco_bo_markers"];
347 for (FileNodeIterator it = markers.begin();it!=markers.end();++it,i++) {
348 at(i).id=(*it)[
"id"];
349 int ncorners=(*it)[
"ncorners"];
350 at(i).resize(ncorners);
351 FileNode FnCorners=(*it)[
"corners"];
353 for (FileNodeIterator itc = FnCorners.begin();itc!=FnCorners.end();++itc,c++) {
354 vector<float> coordinates2d;
355 (*itc)>>coordinates2d;
356 if(coordinates2d.size()!=2)
357 throw cv::Exception ( 81818,
"Board::readFromFile",
"invalid file type 2" ,__FILE__,__LINE__ );
359 point.x=coordinates2d[0];
360 point.y=coordinates2d[1];
361 at(i).push_back(point);
365 conf.readFromFile(fs);
374 if (!append) ids.clear();
375 for(
size_t i=0;i<size();i++)
376 ids.push_back(at(i).
id);
void saveToFile(string filePath)
BoardConfiguration & operator=(const BoardConfiguration &T)
void readFromFile(string filePath)
void readFromFile(string sfile)
int getIndexOfMarkerId(int id) const
const MarkerInfo & getMarkerInfo(int id) const
void getIdList(vector< int > &ids, bool append=true) const
This class defines a board with several markers. A Board contains several markers so that they are mo...
void glGetModelViewMatrix(double modelview_matrix[16])
void saveToFile(string sfile)
void OgreGetPoseParameters(double position[3], double orientation[4])