43 #include <Eigen/StdVector>    55     void VisualizeMarkerPose(IplImage *
image, 
Camera *
cam, 
double visualize2d_points[12][2], CvScalar color=CV_RGB(255,0,0)) 
const;
    56     virtual void VisualizeMarkerContent(IplImage *image, 
Camera *cam, 
double datatext_point[2], 
double content_point[2]) 
const;
    57     virtual void VisualizeMarkerError(IplImage *image, 
Camera *cam, 
double errortext_point[2]) 
const;
    61     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
    70     void CompareCorners(std::vector<
Point<CvPoint2D64f> > &_marker_corners_img, 
int *orientation, 
double *error);
    73     void CompareContent(std::vector<
Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, 
Camera *cam, 
int *orientation) 
const;
    76     virtual bool UpdateContent(std::vector<
Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, 
Camera *cam, 
int frame_no = 0);
    79     void UpdatePose(std::vector<
Point<CvPoint2D64f> > &_marker_corners_img, 
Camera *cam, 
int orientation, 
int frame_no = 0, 
bool update_pose = 
true);
    83     virtual bool DecodeContent(
int *orientation);
    88       return marker_content;
    92     void SaveMarkerImage(
const char *
filename, 
int save_res = 0) 
const;
    95     void ScaleMarkerToImage(IplImage *image) 
const;
    98     void Visualize(IplImage *image, 
Camera *cam, CvScalar color=CV_RGB(255,0,0)) 
const;
   100     void SetMarkerSize(
double _edge_length = 0, 
int _res = 0, 
double _margin = 0);
   110     Marker(
double _edge_length = 0, 
int _res = 0, 
double _margin = 0);
   118     virtual unsigned long GetId()
 const { 
return 0; }
   119     virtual void SetId(
unsigned long _id) {};
   144     double GetError(
int errors = (MARGIN_ERROR | DECODE_ERROR))
 const {
   147       if (errors & MARGIN_ERROR) {error+=margin_error; count++;}
   148       if (errors & DECODE_ERROR) {error+=decode_error; count++;}
   149       if (errors & TRACK_ERROR) {error+=track_error; count++;}
   154       if (error_type == MARGIN_ERROR) margin_error = value;
   155       else if (error_type == DECODE_ERROR) decode_error = value;
   156       else if (error_type == TRACK_ERROR) track_error = value;
   158     static const int MARGIN_ERROR=1;
   159     static const int DECODE_ERROR=2;
   160     static const int TRACK_ERROR=4;
   186 #ifdef VISUALIZE_MARKER_POINTS   187     std::vector<PointDouble> marker_allpoints_img;
   197     int default_res() { std::cout<<
"MarkerArtoolkit::default_res"<<std::endl; 
return 3; }
   201     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
   206     Marker(_edge_length, (_res?_res:3), (_margin?_margin:1.5))
   210     unsigned long GetId()
 const { 
return id; }
   211     void SetId(
unsigned long _id) { 
id = _id; }
   213     bool DecodeContent(
int *orientation);
   215     void SetContent(
unsigned long _id);
   224     virtual void VisualizeMarkerContent(IplImage *image, 
Camera *cam, 
double datatext_point[2], 
double content_point[2]) 
const;
   225     void DecodeOrientation(
int *error, 
int *total, 
int *orientation);
   226     int DecodeCode(
int orientation, 
BitsetExt *bs, 
int *erroneous, 
int *total, 
unsigned char* content_type);
   227     void Read6bitStr(
BitsetExt *bs, 
char *
s, 
size_t s_max_len);
   229     int UsableDataBits(
int marker_res, 
int hamming);
   233     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
   234     static const int MAX_MARKER_STRING_LEN=2048;
   239       MARKER_CONTENT_TYPE_HTTP
   246       char                      str[MAX_MARKER_STRING_LEN]; 
   254   MarkerData(
double _edge_length = 0, 
int _res = 0, 
double _margin = 0) : 
   255     Marker(_edge_length, _res, (_margin?_margin:2))
   259     unsigned long GetId()
 const { 
return data.id; }
   261     void SetId(
unsigned long _id) { data.id = _id; }
   266     virtual bool UpdateContent(std::vector<
Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, 
Camera *cam, 
int frame_no = 0);
   269     bool DecodeContent(
int *orientation);
   272     void SetContent(
MarkerContentType content_type, 
unsigned long id, 
const char *str, 
bool force_strong_hamming=
false, 
bool verbose=
false);
   283     virtual const Marker* operator->() = 0;
   296   EIGEN_MAKE_ALIGNED_OPERATOR_NEW    
   312       return (_i == pother->_i);
   317       return (_i != pother->_i);
   340     const_iterator_aligntype 
_i;
 
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)
const Marker * operator->()
pcl::PointCloud< ARPoint > ARCloud
unsigned char content_type
std::vector< PointDouble > marker_corners_img
Marker corners in image coordinates. 
CvMat * GetContent() const 
Returns the content as a matrix. 
This file implements bit set handling. 
This file implements a camera used for projecting points and computing homographies. 
virtual unsigned long GetId() const 
Get id for this marker This is used e.g. in MarkerDetector to associate a marker id with an appropria...
TFSIMD_FORCE_INLINE bool operator==(const Matrix3x3 &m1, const Matrix3x3 &m2)
void SetError(int error_type, double value)
Set the marker error estimate. 
std::vector< PointDouble > marker_margin_w
Samples to be used in figuring out min/max for thresholding. 
bool operator!=(const MarkerIterator &other)
virtual void SetId(unsigned long _id)
MarkerData contains matrix of Hamming encoded data. 
bool operator==(const MarkerIterator &other)
void SetId(unsigned long _id)
Set the ID. 
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
const_iterator_aligntype _begin
MarkerIterator & operator++()
std::vector< PointDouble > marker_margin_b
Samples to be used in figuring out min/max for thresholding. 
Pose pose
The current marker Pose. 
MarkerIteratorImpl(const_iterator_aligntype i)
const_iterator_aligntype _i
double GetError(int errors=(MARGIN_ERROR|DECODE_ERROR)) const 
Get marker detection error estimate. 
Pose representation derived from the Rotation class 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool valid
TFSIMD_FORCE_INLINE bool operator!=(const Vector3 &other) const 
std::vector< PointDouble > ros_marker_points_img
Marker points in image coordinates. 
Basic 2D Marker functionality. 
unsigned long GetId() const 
Get ID for recognizing this marker. 
const Marker * operator*()
This file implements generic utility functions and a serialization interface. 
Iterator type for traversing templated Marker vector without the template. 
double GetMarkerEdgeLength() const 
Get edge length (to support different size markers. 
std::vector< PointDouble > marker_points
Marker color points in marker coordinates. 
Iterator implementation for traversing templated Marker vector without the template. 
MarkerIteratorImpl & operator=(const MarkerIteratorImpl &other)
This file implements a pose. 
MarkerData(double _edge_length=0, int _res=0, double _margin=0)
Default constructor. 
An extended Bitset ( BitsetExt ) for handling e.g. Hamming encoding/decoding. 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::vector< T, Eigen::aligned_allocator< T > >::const_iterator const_iterator_aligntype
This file defines library export definitions, version numbers and build information. 
ar_track_alvar::ARCloud ros_corners_3D
std::vector< PointDouble > marker_corners
Marker corners in marker coordinates.