31 #include <opencv2/highgui/highgui.hpp>    32 #include <opencv2/imgproc/imgproc.hpp>    33 #include <opencv2/calib3d/calib3d.hpp>    37 using namespace aruco;
    52 class CmdLineParser{
int argc; 
char **argv; 
public:  
CmdLineParser(
int _argc,
char **_argv):argc(_argc),argv(_argv){}  
bool operator[] ( 
string param ) {
int idx=-1;  
for ( 
int i=0; i<argc && idx==-1; i++ ) 
if ( 
string ( argv[i] ) ==param ) idx=i;    
return ( idx!=-1 ) ;    } 
string operator()(
string param,
string defvalue=
"-1"){
int idx=-1;    
for ( 
int i=0; i<argc && idx==-1; i++ ) 
if ( 
string ( argv[i] ) ==param ) idx=i; 
if ( idx==-1 ) 
return defvalue;   
else  return ( argv[  idx+1] ); }};
    56 void getMarker2d_3d(vector<cv::Point2f> &p2d, vector<cv::Point3f> &p3d, 
const vector< Marker >&markers_detected,
const MarkerMap &bc){
    60     for(
size_t i=0;i<markers_detected.size();i++){
    63         for(
size_t j=0;j<bc.size() &&fidx==-1;j++)
    64             if (bc[j].
id==markers_detected[i].
id ) fidx=j;
    67                 p2d.push_back(markers_detected[i][j]);
    68                 p3d.push_back(bc[fidx][j]);
    72  cout<<
"points added"<<endl;
    85 int main(
int argc, 
char **argv) {
    88         if (argc <3 || cml[
"-h"]){
    89             cerr << 
"Usage: (in.avi|live) out_camera_calibration.yml  [-m markermapConfig.yml (configuration of the board. If use default one (in utils), no need to set this)]    [-size <float> :(value in meters of a marker. If you provide a board that contains that information, this is ommited) ] " << endl;
    94         if (cml[
"-m"]) TheMarkerMapConfig.
readFromFile( cml(
"-m"));
   100             cerr<<
"Need to specify the size of the makers (in meters) with -size"<<endl;
   104             TheMarkerMapConfig=TheMarkerMapConfig.
convertToMeters(atof(cml(
"-size").c_str()));
   106         if (
string(argv[1]) == 
"live") {
   112             cerr << 
"Could not open video" << endl;
   126         params.
_subpix_wsize= (15./2000.)*float(TheInputImage.cols) ;
   130         cout<<
"Press 'a'' to add current view to the pool of images used for calibration"<<endl;
   131         cout<<
"Press 'c' to perform calibration"<<endl;
   132         cout<<
"Press 's' to start/stop capture"<<endl;
   133         cv::namedWindow(
"in", 1);
   139         char key = 0,capturing=0;
   144             vector<aruco::Marker> detected_markers=TheMarkerDetector.
detect(TheInputImage);
   145             vector<int> markers_from_set=TheMarkerMapConfig.
getIndices(detected_markers);
   148             for(
auto idx:markers_from_set) detected_markers[idx].draw(
TheInputImageCopy, Scalar(0, 0, 255), 1);
   156             while( (key = cv::waitKey(10))==-1 && !capturing) ; 
   158                 vector<cv::Point2f> p2d;
   159                 vector<cv::Point3f> p3d;
   167             bool calibrate=
false;
   169             if (key==
'c' || (key==27 && 
calib_p2d.size()>2) ) calibrate=
true;
   171                 vector<cv::Mat> vr,vt;
   172                 camp.
CamSize=TheInputImage.size();
   175                 cerr<<
"repj error="<<err<<endl;
   179             if (key==
's') { capturing=!capturing;}
   183     } 
catch (std::exception &ex)
   186         cout << 
"Exception :" << ex.what() << endl;
   209     vector<int> markers_from_set=TheMarkerMapConfig.
getIndices(detected_markers);
   211     for(
auto idx:markers_from_set) detected_markers[idx].draw(
TheInputImageCopy, Scalar(0, 0, 255), 1);
 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
CameraParameters TheCameraParameters
MarkerDetector TheMarkerDetector
void saveToFile(string path, bool inXML=true)
bool isExpressedInMeters() const 
unsigned int default_a4_board_size
string TheOutCameraParams
void setDictionary(std::string dict_type, float error_correction_rate=0)
std::vector< aruco::Marker > detect(const cv::Mat &input)
void readFromFile(string sfile)
void cvTackBarEvents(int pos, void *)
unsigned char default_a4_board[]
MarkerMap TheMarkerMapConfig
void getMarker2d_3d(vector< cv::Point2f > &p2d, vector< cv::Point3f > &p3d, const vector< Marker > &markers_detected, const MarkerMap &bc)
MarkerMap convertToMeters(float markerSize)
Main class for marker detection. 
Parameters of the camera. 
std::string getDictionary() const 
void fromStream(std::istream &str)
double _thresParam1_range
std::vector< int > getIndices(vector< aruco::Marker > &markers)
int main(int argc, char **argv)
VideoCapture TheVideoCapturer
CornerRefinementMethod _cornerMethod
vector< vector< cv::Point3f > > calib_p3d
This class defines a set of markers whose locations are attached to a common reference system...
aruco::CameraParameters camp
vector< vector< cv::Point2f > > calib_p2d