29 #include <opencv2/calib3d/calib3d.hpp> 39 BoardConfiguration::BoardConfiguration() { mInfoType = NONE; }
44 BoardConfiguration::BoardConfiguration(
string filePath)
throw(cv::Exception) {
46 readFromFile(filePath);
63 vector< MarkerInfo >::operator=(T);
73 cv::FileStorage fs(sfile, cv::FileStorage::WRITE);
79 fs <<
"aruco_bc_nmarkers" << (int)size();
80 fs <<
"aruco_bc_mInfoType" << (int)
mInfoType;
81 fs <<
"aruco_bc_markers" 83 for (
size_t i = 0; i < size(); i++) {
89 for (
int c = 0; c < at(i).size(); c++)
103 cv::FileStorage fs(sfile, cv::FileStorage::READ);
105 }
catch (std::exception &ex) {
106 throw cv::Exception(81818,
"BoardConfiguration::readFromFile", ex.what() + string(
" file=)") + sfile, __FILE__, __LINE__);
116 if (fs[
"aruco_bc_nmarkers"].name() !=
"aruco_bc_nmarkers")
117 throw cv::Exception(81818,
"BoardConfiguration::readFromFile",
"invalid file type", __FILE__, __LINE__);
118 fs[
"aruco_bc_nmarkers"] >> aux;
121 cv::FileNode markers = fs[
"aruco_bc_markers"];
123 for (FileNodeIterator it = markers.begin(); it != markers.end(); ++it, i++) {
124 at(i).id = (*it)[
"id"];
125 FileNode FnCorners = (*it)[
"corners"];
126 for (FileNodeIterator itc = FnCorners.begin(); itc != FnCorners.end(); ++itc) {
127 vector< float > coordinates3d;
128 (*itc) >> coordinates3d;
129 if (coordinates3d.size() != 3)
130 throw cv::Exception(81818,
"BoardConfiguration::readFromFile",
"invalid file type 3", __FILE__, __LINE__);
131 cv::Point3f point(coordinates3d[0], coordinates3d[1], coordinates3d[2]);
132 at(i).push_back(point);
141 for (
size_t i = 0; i < size(); i++)
150 for (
size_t i = 0; i < size(); i++)
153 throw cv::Exception(111,
"BoardConfiguration::getMarkerInfo",
"Marker with the id given is not found", __FILE__, __LINE__);
161 bool invalid =
false;
162 for (
int i = 0; i < 3 && !invalid; i++) {
163 if (Tvec.at<
float >(i, 0) != -999999)
165 if (Rvec.at<
float >(i, 0) != -999999)
169 throw cv::Exception(9002,
"extrinsic parameters are not set",
"Marker::getModelViewMatrix", __FILE__, __LINE__);
170 Mat Rot(3, 3, CV_32FC1), Jacob;
171 Rodrigues(Rvec, Rot, Jacob);
174 for (
int i = 0; i < 3; i++)
175 for (
int j = 0; j < 3; j++)
176 para[i][j] = Rot.at<
float >(i, j);
178 para[0][3] = Tvec.at<
float >(0, 0);
179 para[1][3] = Tvec.at<
float >(1, 0);
180 para[2][3] = Tvec.at<
float >(2, 0);
183 modelview_matrix[0 + 0 * 4] = para[0][0];
185 modelview_matrix[0 + 1 * 4] = para[0][1];
186 modelview_matrix[0 + 2 * 4] = para[0][2];
187 modelview_matrix[0 + 3 * 4] = para[0][3];
189 modelview_matrix[1 + 0 * 4] = para[1][0];
190 modelview_matrix[1 + 1 * 4] = para[1][1];
191 modelview_matrix[1 + 2 * 4] = para[1][2];
192 modelview_matrix[1 + 3 * 4] = para[1][3];
194 modelview_matrix[2 + 0 * 4] = -para[2][0];
195 modelview_matrix[2 + 1 * 4] = -para[2][1];
196 modelview_matrix[2 + 2 * 4] = -para[2][2];
197 modelview_matrix[2 + 3 * 4] = -para[2][3];
198 modelview_matrix[3 + 0 * 4] = 0.0;
199 modelview_matrix[3 + 1 * 4] = 0.0;
200 modelview_matrix[3 + 2 * 4] = 0.0;
201 modelview_matrix[3 + 3 * 4] = 1.0;
203 modelview_matrix[12] *= scale;
204 modelview_matrix[13] *= scale;
205 modelview_matrix[14] *= scale;
215 bool invalid =
false;
216 for (
int i = 0; i < 3 && !invalid; i++) {
217 if (Tvec.at<
float >(i, 0) != -999999)
219 if (Rvec.at<
float >(i, 0) != -999999)
223 throw cv::Exception(9003,
"extrinsic parameters are not set",
"Marker::getModelViewMatrix", __FILE__, __LINE__);
226 position[0] = -Tvec.ptr<
float >(0)[0];
227 position[1] = -Tvec.ptr<
float >(0)[1];
228 position[2] = +Tvec.ptr<
float >(0)[2];
231 cv::Mat Rot(3, 3, CV_32FC1);
232 cv::Rodrigues(Rvec, Rot);
237 stAxes[0][0] = -Rot.at<
float >(0, 0);
238 stAxes[0][1] = -Rot.at<
float >(1, 0);
239 stAxes[0][2] = +Rot.at<
float >(2, 0);
241 stAxes[1][0] = -Rot.at<
float >(0, 1);
242 stAxes[1][1] = -Rot.at<
float >(1, 1);
243 stAxes[1][2] = +Rot.at<
float >(2, 1);
245 stAxes[2][0] = stAxes[0][1] * stAxes[1][2] - stAxes[0][2] * stAxes[1][1];
246 stAxes[2][1] = -stAxes[0][0] * stAxes[1][2] + stAxes[0][2] * stAxes[1][0];
247 stAxes[2][2] = stAxes[0][0] * stAxes[1][1] - stAxes[0][1] * stAxes[1][0];
251 axes[0][0] = stAxes[0][0];
252 axes[1][0] = stAxes[0][1];
253 axes[2][0] = stAxes[0][2];
255 axes[0][1] = stAxes[1][0];
256 axes[1][1] = stAxes[1][1];
257 axes[2][1] = stAxes[1][2];
259 axes[0][2] = stAxes[2][0];
260 axes[1][2] = stAxes[2][1];
261 axes[2][2] = stAxes[2][2];
265 double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
270 fRoot = sqrt(fTrace + 1.0);
271 orientation[0] = 0.5 * fRoot;
273 orientation[1] = (axes[2][1] - axes[1][2]) * fRoot;
274 orientation[2] = (axes[0][2] - axes[2][0]) * fRoot;
275 orientation[3] = (axes[1][0] - axes[0][1]) * fRoot;
278 static unsigned int s_iNext[3] = {1, 2, 0};
280 if (axes[1][1] > axes[0][0])
282 if (axes[2][2] > axes[i][i])
284 unsigned int j = s_iNext[i];
285 unsigned int k = s_iNext[j];
287 fRoot = sqrt(axes[i][i] - axes[j][j] - axes[k][k] + 1.0);
288 double *apkQuat[3] = {&orientation[1], &orientation[2], &orientation[3]};
289 *apkQuat[i] = 0.5 * fRoot;
291 orientation[0] = (axes[k][j] - axes[j][k]) * fRoot;
292 *apkQuat[j] = (axes[j][i] + axes[i][j]) * fRoot;
293 *apkQuat[k] = (axes[k][i] + axes[i][k]) * fRoot;
299 void Board::draw(cv::Mat &im, cv::Scalar color,
int lineWidth,
bool writeId) {
300 for (
size_t i = 0; i < size(); i++) {
301 at(i).draw(im, color, lineWidth, writeId);
308 cv::FileStorage fs(filePath, cv::FileStorage::WRITE);
310 fs <<
"aruco_bo_rvec" << Rvec;
311 fs <<
"aruco_bo_tvec" << Tvec;
313 fs <<
"aruco_bo_nmarkers" << (int)size();
314 fs <<
"aruco_bo_markers" 316 for (
size_t i = 0; i < size(); i++) {
321 for (
int c = 0; c < at(i).size(); c++)
337 cv::FileStorage fs(filePath, cv::FileStorage::READ);
338 if (fs[
"aruco_bo_nmarkers"].name() !=
"aruco_bo_nmarkers")
339 throw cv::Exception(81818,
"Board::readFromFile",
"invalid file type:", __FILE__, __LINE__);
345 fs[
"aruco_bo_nmarkers"] >> aux;
347 fs[
"aruco_bo_rvec"] >> Rvec;
348 fs[
"aruco_bo_tvec"] >> Tvec;
350 cv::FileNode markers = fs[
"aruco_bo_markers"];
352 for (FileNodeIterator it = markers.begin(); it != markers.end(); ++it, i++) {
353 at(i).id = (*it)[
"id"];
354 int ncorners = (*it)[
"ncorners"];
355 at(i).resize(ncorners);
356 FileNode FnCorners = (*it)[
"corners"];
358 for (FileNodeIterator itc = FnCorners.begin(); itc != FnCorners.end(); ++itc, c++) {
359 vector< float > coordinates2d;
360 (*itc) >> coordinates2d;
361 if (coordinates2d.size() != 2)
362 throw cv::Exception(81818,
"Board::readFromFile",
"invalid file type 2", __FILE__, __LINE__);
364 point.x = coordinates2d[0];
365 point.y = coordinates2d[1];
366 at(i).push_back(point);
370 conf.readFromFile(fs);
378 for (
size_t i = 0; i < size(); i++)
379 ids.push_back(at(i).
id);
void saveToFile(string filePath)
const MarkerInfo & getMarkerInfo(int id) const
BoardConfiguration & operator=(const BoardConfiguration &T)
void readFromFile(string filePath)
int getIndexOfMarkerId(int id) const
void readFromFile(string sfile)
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 draw(cv::Mat &im, cv::Scalar color, int lineWidth=1, bool writeId=true)
void OgreGetPoseParameters(double position[3], double orientation[4])