TagDetection.h
Go to the documentation of this file.
00001 #ifndef TAGDETECTION_H
00002 #define TAGDETECTION_H
00003 
00004 #include <Eigen/Dense>
00005 
00006 #include "opencv2/opencv.hpp"
00007 
00008 #include <utility>
00009 #include <vector>
00010 
00011 namespace AprilTags {
00012 
00013 struct TagDetection {
00014 
00016   TagDetection();
00017 
00019   TagDetection(int id);
00020 
00022   bool good;
00023 
00025   long long obsCode;
00026 
00028   long long code;
00029 
00031   int id;
00032 
00034   int hammingDistance;
00035   
00037   int rotation;
00038 
00041   /*  The points travel counter-clockwise around the target, always
00042    *  starting from the same corner of the tag.
00043    */
00044   std::pair<float,float> p[4];
00045 
00047   std::pair<float,float> cxy;
00048 
00050 
00051   float observedPerimeter;
00052 
00054   /*  Both the input and output coordinates are 2D homogeneous vectors, with y = Hx.
00055    *  'y' are pixel coordinates, 'x' are tag-relative coordinates. Tag coordinates span
00056    *  from (-1,-1) to (1,1). The orientation of the homography reflects the orientation
00057    *  of the target.
00058    */
00059   Eigen::Matrix3d homography;
00060 
00062   float getXYOrientation() const;
00063 
00065   std::pair<float,float> hxy;
00066 
00068   std::pair<float,float> interpolate(float x, float y) const;
00069 
00071   bool overlapsTooMuch(const TagDetection &other) const;
00072 
00074   /* Returns the relative location and orientation of the tag using a
00075      4x4 homogeneous transformation matrix (see Hartley&Zisserman,
00076      Multi-View Geometry, 2003). Requires knowledge of physical tag
00077      size (side length of black square in meters) as well as camera
00078      calibration (focal length and principal point); Result is in
00079      camera frame (z forward, x right, y down)
00080   */
00081   Eigen::Matrix4d getRelativeTransform(double tag_size, double fx, double fy,
00082                                        double px, double py) const;
00083 
00085   // Result is in object frame (x forward, y left, z up)
00086   void getRelativeTranslationRotation(double tag_size, double fx, double fy, double px, double py,
00087                                       Eigen::Vector3d& trans, Eigen::Matrix3d& rot) const;
00088 
00090   void draw(cv::Mat& image) const;
00091 };
00092 
00093 } // namespace
00094 
00095 #endif


apriltags
Author(s): Michael Kaess, Hordur Johannson
autogenerated on Thu Jun 6 2019 20:53:23