aruco/src/aruco/boarddetector.cpp
Go to the documentation of this file.
1 #pragma GCC diagnostic warning "-Wuninitialized"
2 /*****************************
3 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification, are
6 permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this list of
9  conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice, this list
12  of conditions and the following disclaimer in the documentation and/or other materials
13  provided with the distribution.
14 
15 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
16 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
17 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
18 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
19 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
20 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
21 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
22 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
23 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
24 
25 The views and conclusions contained in the software and documentation are those of the
26 authors and should not be interpreted as representing official policies, either expressed
27 or implied, of Rafael Muñoz Salinas.
28 ********************************/
29 #include <aruco/boarddetector.h>
30 #define _USE_MATH_DEFINES
31 #include <math.h>
32 #include <cstdlib>
33 #include <ctime>
34 #include <cassert>
35 #include <fstream>
36 using namespace std;
37 using namespace cv;
38 namespace aruco
39 {
40 
41  BoardDetector::BoardDetector(bool setYPerpendicular)
42  : _setYPerpendicular(setYPerpendicular),
43  _areParamsSet(false),
44  _markerSize(0)
45  {}
49  void BoardDetector::setParams(const BoardConfiguration &bc,const CameraParameters &cp, float markerSizeMeters)
50  {
51  _camParams = cp;
52  _markerSize = markerSizeMeters;
53  _bconf = bc;
54  _areParamsSet = true;
55  }
56 
58  {
59  _bconf = bc;
60  _areParamsSet = true;
61  }
62 
63 
64  float BoardDetector::detect(const cv::Mat &im)throw (cv::Exception)
65  {
67 
68  float res;
69 
70  if (_camParams.isValid())
73  return res;
74  }
75 
76  float BoardDetector::detect ( const vector<Marker> &detectedMarkers,const BoardConfiguration &BConf, Board &Bdetected,const CameraParameters &cp, float markerSizeMeters ) throw ( cv::Exception )
77  {
78  return detect ( detectedMarkers, BConf,Bdetected,cp.CameraMatrix,cp.Distorsion,markerSizeMeters );
79  }
80 
81  float BoardDetector::detect ( const vector<Marker> &detectedMarkers,const BoardConfiguration &BConf, Board &Bdetected, Mat camMatrix,Mat distCoeff,float markerSizeMeters ) throw ( cv::Exception )
82  {
83  if (BConf.size()==0) throw cv::Exception(8881,"BoardDetector::detect","Invalid BoardConfig that is empty",__FILE__,__LINE__);
84  if (BConf[0].size()<2) throw cv::Exception(8881,"BoardDetector::detect","Invalid BoardConfig that is empty 2",__FILE__,__LINE__);
85  //compute the size of the markers in meters, which is used for some routines(mostly drawing)
86  float ssize;
87  if ( BConf.mInfoType==BoardConfiguration::PIX && markerSizeMeters>0 ) ssize=markerSizeMeters;
88  else if ( BConf.mInfoType==BoardConfiguration::METERS )
89  {
90  ssize=cv::norm ( BConf[0][0]-BConf[0][1] );
91  }
92 
93  // cout<<"markerSizeMeters="<<markerSizeMeters<<endl;
94  Bdetected.clear();
96  for ( unsigned int i=0;i<detectedMarkers.size();i++ )
97  {
98  int idx=BConf.getIndexOfMarkerId(detectedMarkers[i].id);
99  if (idx!=-1) {
100  Bdetected.push_back ( detectedMarkers[i] );
101  Bdetected.back().ssize=ssize;
102  }
103  }
104  //copy configuration
105  Bdetected.conf=BConf;
106  //
107 
108  bool hasEnoughInfoForRTvecCalculation=false;
109  if ( Bdetected.size() >=1 )
110  {
111  if ( camMatrix.rows!=0 )
112  {
113  if ( markerSizeMeters>0 && BConf.mInfoType==BoardConfiguration::PIX ) hasEnoughInfoForRTvecCalculation=true;
114  else if ( BConf.mInfoType==BoardConfiguration::METERS ) hasEnoughInfoForRTvecCalculation=true;
115  }
116  }
117 
118  //calculate extrinsic if there is information for that
119  if ( hasEnoughInfoForRTvecCalculation )
120  {
121  //calculate the size of the markers in meters if expressed in pixels
122  double marker_meter_per_pix=0;
123  if ( BConf.mInfoType==BoardConfiguration::PIX ) marker_meter_per_pix=markerSizeMeters / cv::norm ( BConf[0][0]-BConf[0][1] );
124  else marker_meter_per_pix=1;//to avoind interferring the process below
125 
126  // now, create the matrices for finding the extrinsics
127  Mat objPoints ( 4*Bdetected.size(),3,CV_32FC1 );
128  Mat imagePoints ( 4*Bdetected.size(),2,CV_32FC1 );
129  //size in meters of inter-marker distance
130 
131  for ( size_t i=0;i<Bdetected.size();i++ )
132  {
133  int idx=Bdetected.conf.getIndexOfMarkerId(Bdetected[i].id);
134  assert(idx!=-1);
135  for ( int p=0;p<4;p++ )
136  {
137  imagePoints.at<float> ( ( i*4 ) +p,0 ) =Bdetected[i][p].x;
138  imagePoints.at<float> ( ( i*4 ) +p,1 ) =Bdetected[i][p].y;
139  const aruco::MarkerInfo &Minfo=Bdetected.conf.getMarkerInfo( Bdetected[i].id);
140 
141  objPoints.at<float> ( ( i*4 ) +p,0 ) = Minfo[p].x*marker_meter_per_pix;
142  objPoints.at<float> ( ( i*4 ) +p,1 ) = Minfo[p].y*marker_meter_per_pix;
143  objPoints.at<float> ( ( i*4 ) +p,2 ) = Minfo[p].z*marker_meter_per_pix;
144  // cout<<objPoints.at<float>( (i*4)+p,0)<<" "<<objPoints.at<float>( (i*4)+p,1)<<" "<<objPoints.at<float>( (i*4)+p,2)<<endl;
145  }
146  }
147  if (distCoeff.total()==0) distCoeff=cv::Mat::zeros(1,4,CV_32FC1 );
148 
149  cv::Mat rvec,tvec;
150  cv::solvePnP(objPoints,imagePoints,camMatrix,distCoeff,rvec,tvec );
151  rvec.convertTo(Bdetected.Rvec,CV_32FC1);
152  tvec.convertTo(Bdetected.Tvec,CV_32FC1);
153  //now, rotate 90 deg in X so that Y axis points up
154  if (_setYPerpendicular)
155  rotateXAxis ( Bdetected.Rvec );
156  // cout<<Bdetected.Rvec.at<float>(0,0)<<" "<<Bdetected.Rvec.at<float>(1,0)<<" "<<Bdetected.Rvec.at<float>(2,0)<<endl;
157  // cout<<Bdetected.Tvec.at<float>(0,0)<<" "<<Bdetected.Tvec.at<float>(1,0)<<" "<<Bdetected.Tvec.at<float>(2,0)<<endl;
158  }
159 
160  float prob=float( Bdetected.size() ) /double ( Bdetected.conf.size() );
161  return prob;
162  }
163 
164  void BoardDetector::rotateXAxis ( Mat &rotation )
165  {
166  cv::Mat R ( 3,3,CV_32FC1 );
167  Rodrigues ( rotation, R );
168  //create a rotation matrix for x axis
169  cv::Mat RX=cv::Mat::eye ( 3,3,CV_32FC1 );
170  float angleRad=-M_PI/2;
171  RX.at<float> ( 1,1 ) =cos ( angleRad );
172  RX.at<float> ( 1,2 ) =-sin ( angleRad );
173  RX.at<float> ( 2,1 ) =sin ( angleRad );
174  RX.at<float> ( 2,2 ) =cos ( angleRad );
175  //now multiply
176  R=R*RX;
177  //finally, the the rodrigues back
178  Rodrigues ( R,rotation );
179 
180  }
181 
182 }
183 
void detect(const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1, bool setYPerpendicular=true)
void setParams(const BoardConfiguration &bc, const CameraParameters &cp, float markerSizeMeters=-1)
BoardConfiguration conf
float detect(const cv::Mat &im)
const MarkerInfo & getMarkerInfo(int id) const
This class defines a board with several markers. A Board contains several markers so that they are mo...
void rotateXAxis(cv::Mat &rotation)


lidar_camera_calibration
Author(s):
autogenerated on Sat Feb 6 2021 03:39:37