Marker.h
Go to the documentation of this file.
00001 /*
00002  * This file is part of ALVAR, A Library for Virtual and Augmented Reality.
00003  *
00004  * Copyright 2007-2012 VTT Technical Research Centre of Finland
00005  *
00006  * Contact: VTT Augmented Reality Team <alvar.info@vtt.fi>
00007  *          <http://www.vtt.fi/multimedia/alvar.html>
00008  *
00009  * ALVAR is free software; you can redistribute it and/or modify it under the
00010  * terms of the GNU Lesser General Public License as published by the Free
00011  * Software Foundation; either version 2.1 of the License, or (at your option)
00012  * any later version.
00013  *
00014  * This library is distributed in the hope that it will be useful, but WITHOUT
00015  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00016  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
00017  * for more details.
00018  *
00019  * You should have received a copy of the GNU Lesser General Public License
00020  * along with ALVAR; if not, see
00021  * <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>.
00022  */
00023 
00024 #ifndef MARKER_H
00025 #define MARKER_H
00026 
00034 #include "Alvar.h"
00035 #include <iostream>
00036 #include <algorithm>
00037 #include "Util.h"
00038 #include "Camera.h"
00039 #include "Pose.h"
00040 #include "Bitset.h"
00041 #include <vector>
00042 #include "filter/kinect_filtering.h"
00043 #include <Eigen/StdVector>
00044 
00045 namespace alvar {
00046 
00052   class ALVAR_EXPORT Marker
00053   {
00054   protected:
00055     void VisualizeMarkerPose(IplImage *image, Camera *cam, double visualize2d_points[12][2], CvScalar color=CV_RGB(255,0,0)) const;
00056     virtual void VisualizeMarkerContent(IplImage *image, Camera *cam, double datatext_point[2], double content_point[2]) const;
00057     virtual void VisualizeMarkerError(IplImage *image, Camera *cam, double errortext_point[2]) const;
00058     bool UpdateContentBasic(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int frame_no = 0);
00059 
00060   public:
00061     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
00062     bool valid;
00063 
00070     void CompareCorners(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, int *orientation, double *error);
00073     void CompareContent(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int *orientation) const;
00076     virtual bool UpdateContent(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int frame_no = 0);
00079     void UpdatePose(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, Camera *cam, int orientation, int frame_no = 0, bool update_pose = true);
00083     virtual bool DecodeContent(int *orientation);
00084         
00087     CvMat *GetContent() const {
00088       return marker_content;
00089     }
00092     void SaveMarkerImage(const char *filename, int save_res = 0) const;
00095     void ScaleMarkerToImage(IplImage *image) const;
00098     void Visualize(IplImage *image, Camera *cam, CvScalar color=CV_RGB(255,0,0)) const;
00100     void SetMarkerSize(double _edge_length = 0, int _res = 0, double _margin = 0);
00102     double GetMarkerEdgeLength() const { return edge_length; }
00104     ~Marker();
00110     Marker(double _edge_length = 0, int _res = 0, double _margin = 0);
00112     Marker(const Marker& m);
00118     virtual unsigned long GetId() const { return 0; }
00119     virtual void SetId(unsigned long _id) {};
00120 
00126     int GetRes() const { return res; }
00127 
00132     double GetMargin() const { return margin; }
00133 
00136     Pose pose;
00144     double GetError(int errors = (MARGIN_ERROR | DECODE_ERROR)) const {
00145       int count = 0;
00146       double error = 0;
00147       if (errors & MARGIN_ERROR) {error+=margin_error; count++;}
00148       if (errors & DECODE_ERROR) {error+=decode_error; count++;}
00149       if (errors & TRACK_ERROR) {error+=track_error; count++;}
00150       return error/count;
00151     }
00153     void SetError(int error_type, double value) {
00154       if (error_type == MARGIN_ERROR) margin_error = value;
00155       else if (error_type == DECODE_ERROR) decode_error = value;
00156       else if (error_type == TRACK_ERROR) track_error = value;
00157     }
00158     static const int MARGIN_ERROR=1;
00159     static const int DECODE_ERROR=2;
00160     static const int TRACK_ERROR=4;
00161   protected:
00162     double margin_error;
00163     double decode_error;
00164     double track_error;
00165     double edge_length;
00166     int res;
00167     double margin;
00168     CvMat *marker_content;
00169 
00170   public:
00171       
00173     std::vector<PointDouble> marker_points;
00175     std::vector<PointDouble> marker_corners;
00177     std::vector<PointDouble> marker_corners_img;
00179     std::vector<PointDouble> ros_marker_points_img;
00180     ar_track_alvar::ARCloud ros_corners_3D;
00181     int ros_orientation;
00183     std::vector<PointDouble> marker_margin_w;
00185     std::vector<PointDouble> marker_margin_b;
00186 #ifdef VISUALIZE_MARKER_POINTS
00187     std::vector<PointDouble> marker_allpoints_img;
00188 #endif
00189   };
00190 
00194   class ALVAR_EXPORT MarkerArtoolkit : public Marker
00195   {
00196   protected:
00197     int default_res() { std::cout<<"MarkerArtoolkit::default_res"<<std::endl; return 3; }
00198     double default_margin() { return 1.5; }
00199 
00200   public:
00201     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
00203     unsigned long id;
00205   MarkerArtoolkit(double _edge_length = 0, int _res = 0, double _margin = 0) : 
00206     Marker(_edge_length, (_res?_res:3), (_margin?_margin:1.5))
00207       {
00208       }
00210     unsigned long GetId() const { return id; }
00211     void SetId(unsigned long _id) { id = _id; }
00213     bool DecodeContent(int *orientation);
00215     void SetContent(unsigned long _id);
00216   };
00217 
00221   class ALVAR_EXPORT MarkerData : public Marker
00222   {
00223   protected:
00224     virtual void VisualizeMarkerContent(IplImage *image, Camera *cam, double datatext_point[2], double content_point[2]) const;
00225     void DecodeOrientation(int *error, int *total, int *orientation);
00226     int DecodeCode(int orientation, BitsetExt *bs, int *erroneous, int *total, unsigned char* content_type);
00227     void Read6bitStr(BitsetExt *bs, char *s, size_t s_max_len);
00228     void Add6bitStr(BitsetExt *bs, char *s);
00229     int UsableDataBits(int marker_res, int hamming);
00230     bool DetectResolution(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam);
00231 
00232   public:
00233     EIGEN_MAKE_ALIGNED_OPERATOR_NEW  
00234     static const int MAX_MARKER_STRING_LEN=2048;
00235     enum MarkerContentType {
00236       MARKER_CONTENT_TYPE_NUMBER,
00237       MARKER_CONTENT_TYPE_STRING,
00238       MARKER_CONTENT_TYPE_FILE,
00239       MARKER_CONTENT_TYPE_HTTP
00240     };
00241     unsigned char       content_type;
00242 
00244     union {
00245       unsigned long     id;                                                     
00246       char                      str[MAX_MARKER_STRING_LEN]; 
00247     } data;
00248 
00254   MarkerData(double _edge_length = 0, int _res = 0, double _margin = 0) : 
00255     Marker(_edge_length, _res, (_margin?_margin:2))
00256       {
00257       }
00259     unsigned long GetId() const { return data.id; }
00261     void SetId(unsigned long _id) { data.id = _id; }
00266     virtual bool UpdateContent(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int frame_no = 0);
00269     bool DecodeContent(int *orientation);
00272     void SetContent(MarkerContentType content_type, unsigned long id, const char *str, bool force_strong_hamming=false, bool verbose=false);
00273   };
00274 
00277   class ALVAR_EXPORT MarkerIterator : public std::iterator<std::forward_iterator_tag, Marker*> {
00278   public:
00279     virtual bool operator==(const MarkerIterator& other) = 0;
00280     virtual bool operator!=(const MarkerIterator& other) = 0;
00281     virtual MarkerIterator& operator++() = 0;
00282     virtual const Marker* operator*() = 0;
00283     virtual const Marker* operator->() = 0;
00284     virtual MarkerIterator& reset() = 0;
00285 
00286     void *_data;
00287   };
00288 
00293   template<typename T>
00294     class ALVAR_EXPORT MarkerIteratorImpl : public MarkerIterator {
00295   public:
00296   EIGEN_MAKE_ALIGNED_OPERATOR_NEW    
00297   typedef typename std::vector<T, Eigen::aligned_allocator<T> >::const_iterator const_iterator_aligntype;
00298   MarkerIteratorImpl(const_iterator_aligntype i) : _begin(i), _i(i) {
00299       _data = this;
00300     }
00301 
00302     ~MarkerIteratorImpl() {}
00303 
00304     // The assignment and relational operators are straightforward
00305     MarkerIteratorImpl& operator=(const MarkerIteratorImpl& other) {
00306       _i = other._i;
00307       return(*this);
00308     }
00309 
00310     bool operator==(const MarkerIterator& other) {
00311       MarkerIteratorImpl* pother = (MarkerIteratorImpl*)other._data;
00312       return (_i == pother->_i);
00313     }
00314 
00315     bool operator!=(const MarkerIterator& other) {
00316       MarkerIteratorImpl* pother = (MarkerIteratorImpl*)other._data;
00317       return (_i != pother->_i);
00318     }
00319 
00320     MarkerIterator& operator++() {
00321       _i++;
00322       return(*this);
00323     }
00324 
00325     const Marker* operator*() {
00326       return &(*_i);
00327     }
00328 
00329     const Marker* operator->() {
00330       return &(*_i);
00331     }
00332 
00333     MarkerIterator& reset() {
00334       _i = _begin;
00335       return (*this);
00336     }
00337 
00338   private:
00339     const_iterator_aligntype _begin;
00340     const_iterator_aligntype _i;
00341   };
00342 
00343 } // namespace alvar
00344 
00345 #endif


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 21:12:54