38 #include <opencv2/highgui/highgui.hpp>    40 using namespace aruco;
    42 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] ); }};
    45 int main(
int argc, 
char **argv) {
    48         if (argc <4 || cml[
"-h"] ){
    49             cerr << 
"Usage: video.avi  cameraParams.yml  markerSize [-d <dicionary>:ARUCO default] " << endl;
    51             cout<<
"Example to work with apriltags dictionary : video.avi -d TAG36h11"<<endl<<endl;
    61         VideoCapture vreader(argv[1]);
    62         if (vreader.isOpened()) vreader>>InImage;
    63         else{cerr<<
"Could not open input"<<endl;
return -1;}
    66         CamParam.
resize(InImage.size());
    68         float MarkerSize = std::stof(argv[3]);
    73         std::map<uint32_t,MarkerPoseTracker> MTracker;
    79             vreader.retrieve(InImage);
    81             vector< Marker >  Markers=MDetector.
detect(InImage);
    82             for(
auto & marker:Markers)
    83                 MTracker[marker.id].estimatePose(marker,CamParam,MarkerSize);
    86             for (
unsigned int i = 0; i < Markers.size(); i++) {
    87                 cout << Markers[i] << endl;
    88                 Markers[i].draw(InImage, Scalar(0, 0, 255), 2);
    91             if (CamParam.
isValid() && MarkerSize != -1){
    92                 for (
unsigned int i = 0; i < Markers.size(); i++) {
    93                     CvDrawingUtils::draw3dCube(InImage, Markers[i], CamParam);
    94                     CvDrawingUtils::draw3dAxis(InImage, Markers[i], CamParam);
    98             cv::namedWindow(
"in", 1);
    99             cv::imshow(
"in", InImage);
   100         } 
while( 
char(cv::waitKey(0))!=27 && vreader.grab()); 
   103         if (cml[
"-o"]) cv::imwrite(cml(
"-o"), InImage);
   104     } 
catch (std::exception &ex)
   107         cout << 
"Exception :" << ex.what() << endl;
 void setThresholdParams(double param1, double param2)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
void resize(cv::Size size)
int main(int argc, char **argv)
static std::vector< std::string > getDicTypes()
void setDictionary(std::string dict_type, float error_correction_rate=0)
std::vector< aruco::Marker > detect(const cv::Mat &input)
void readFromXMLFile(string filePath)
void setThresholdParamRange(size_t r1=0, size_t r2=0)
Main class for marker detection. 
Parameters of the camera.