29 #include <opencv2/calib3d/calib3d.hpp> 30 #include <opencv2/imgproc/imgproc.hpp> 31 #include <opencv2/highgui/highgui.hpp> 43 MarkerMap::MarkerMap() { mInfoType =
NONE; }
48 MarkerMap::MarkerMap(
string filePath)
throw(cv::Exception) {
50 readFromFile(filePath);
58 void MarkerMap::saveToFile(
string sfile)
throw(cv::Exception) {
60 cv::FileStorage fs(sfile, cv::FileStorage::WRITE);
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" 71 for (
size_t i = 0; i < size(); i++) {
77 for (
size_t c = 0; c < at(i).size(); c++)
89 void MarkerMap::readFromFile(
string sfile)
throw(cv::Exception) {
91 cv::FileStorage fs(sfile, cv::FileStorage::READ);
93 }
catch (std::exception &ex) {
94 throw cv::Exception(81818,
"MarkerMap::readFromFile", ex.what() + string(
" file=)") + sfile, __FILE__, __LINE__);
101 void MarkerMap::readFromFile(cv::FileStorage &fs)
throw(cv::Exception) {
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;
108 fs[
"aruco_bc_mInfoType"] >> mInfoType;
109 cv::FileNode markers = fs[
"aruco_bc_markers"];
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);
124 if (fs[
"aruco_bc_dict"].name()==
"aruco_bc_dict")
125 fs[
"aruco_bc_dict"] >> dictionary;
131 int MarkerMap::getIndexOfMarkerId(
int id)
const {
133 for (
size_t i = 0; i < size(); i++)
141 const Marker3DInfo &MarkerMap::getMarker3DInfo(
int id)
const throw(cv::Exception) {
142 for (
size_t i = 0; i < size(); i++)
145 throw cv::Exception(111,
"MarkerMap::getMarker3DInfo",
"Marker with the id given is not found", __FILE__, __LINE__);
151 bool invalid =
false;
152 for (
int i = 0; i < 3 && !invalid; i++) {
153 if (Tvec.at<
float >(i, 0) != -999999)
155 if (Rvec.at<
float >(i, 0) != -999999)
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);
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);
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);
173 modelview_matrix[0 + 0 * 4] = para[0][0];
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];
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];
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;
193 modelview_matrix[12] *= scale;
194 modelview_matrix[13] *= scale;
195 modelview_matrix[14] *= scale;
203 void __OgreGetPoseParameters(
double position[3],
double orientation[4],
const cv::Mat &Rvec,
const cv::Mat &Tvec)
throw(cv::Exception) {
205 bool invalid =
false;
206 for (
int i = 0; i < 3 && !invalid; i++) {
207 if (Tvec.at<
float >(i, 0) != -999999)
209 if (Rvec.at<
float >(i, 0) != -999999)
213 throw cv::Exception(9003,
"extrinsic parameters are not set",
"Marker::getModelViewMatrix", __FILE__, __LINE__);
216 position[0] = -Tvec.ptr<
float >(0)[0];
217 position[1] = -Tvec.ptr<
float >(0)[1];
218 position[2] = +Tvec.ptr<
float >(0)[2];
221 cv::Mat Rot(3, 3, CV_32FC1);
222 cv::Rodrigues(Rvec, Rot);
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);
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);
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];
241 axes[0][0] = stAxes[0][0];
242 axes[1][0] = stAxes[0][1];
243 axes[2][0] = stAxes[0][2];
245 axes[0][1] = stAxes[1][0];
246 axes[1][1] = stAxes[1][1];
247 axes[2][1] = stAxes[1][2];
249 axes[0][2] = stAxes[2][0];
250 axes[1][2] = stAxes[2][1];
251 axes[2][2] = stAxes[2][2];
255 double fTrace = axes[0][0] + axes[1][1] + axes[2][2];
260 fRoot =
sqrt(fTrace + 1.0);
261 orientation[0] = 0.5 * fRoot;
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;
268 static unsigned int s_iNext[3] = {1, 2, 0};
270 if (axes[1][1] > axes[0][0])
272 if (axes[2][2] > axes[i][i])
274 unsigned int j = s_iNext[i];
275 unsigned int k = s_iNext[j];
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;
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;
290 void MarkerMap::getIdList(std::vector< int > &ids,
bool append)
const {
293 for (
size_t i = 0; i < size(); i++)
294 ids.push_back(at(i).
id);
297 MarkerMap MarkerMap::convertToMeters(
float markerSize_meters)
throw (cv::Exception){
299 if (!isExpressedInPixels())
300 throw cv::Exception(-1,
"The board is not expressed in pixels",
"MarkerMap::convertToMeters", __FILE__, __LINE__);
302 int markerSizePix = cv::norm(at(0)[0] - at(0)[1]);
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;
314 cv::Mat MarkerMap::getImage(
float METER2PIX)
const throw (cv::Exception){
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__);
321 auto Dict=Dictionary::loadPredefined(dictionary);
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());
329 pmax.x=max(
int(p.x+0.5),pmax.x);
330 pmax.y=max(
int(p.y+0.5),pmax.y);
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));
339 vector<Marker3DInfo> p3d=*
this;
343 p-=cv::Point3f(pmin.x,pmax.y,0);
350 float size=cv::norm( m[0]-m[1]);
351 auto im1=Dict.getMarkerImage_id(m.id,
int(size/8));
354 cv::resize(im1,im2,cv::Size(size,size));
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);
364 std::vector<int> MarkerMap::getIndices(vector<aruco::Marker> &markers)
366 std::vector<int> indices;
367 for(
size_t i=0;i<markers.size();i++){
369 for(
size_t j=0;j<size() &&!found;j++){
370 if (markers[i].
id==at(j).id){
372 indices.push_back(i);
378 void MarkerMap::toStream(std::ostream &str){
379 str<<mInfoType<<
" " <<size()<<
" ";
380 for(
size_t i=0;i<size();i++) {at(i).toStream(str); }
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);
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;
392 if (isExpressedInPixels())
393 m_meters=convertToMeters(markerSize);
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()){
399 for(
auto p:marker) p2d.push_back(p);
400 for(
auto p:*it) p3d.push_back(p);
406 cv::solvePnPRansac(p3d,p2d,CameraMatrix,Distorsion,rvec,tvec);
407 return make_pair(rvec,tvec);
void __glGetModelViewMatrix(double modelview_matrix[16], const cv::Mat &Rvec, const cv::Mat &Tvec)
Packet pmax(const Packet &a, const Packet &b)
void __OgreGetPoseParameters(double position[3], double orientation[4], const cv::Mat &Rvec, const cv::Mat &Tvec)
Packet pmin(const Packet &a, const Packet &b)
TFSIMD_FORCE_INLINE const tfScalar & x() const
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...