MultiMarker.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 MULTIMARKER_H
00025 #define MULTIMARKER_H
00026 
00033 #include "Alvar.h"
00034 #include "Rotation.h"
00035 #include "MarkerDetector.h"
00036 #include "Camera.h"
00037 #include "Filter.h"
00038 #include "FileFormat.h"
00039 
00040 namespace alvar {
00041 
00045 class ALVAR_EXPORT MultiMarker {
00046 
00047 
00048 private:
00049 
00050         bool SaveXML(const char* fname);
00051         bool SaveText(const char* fname);
00052         bool LoadText(const char* fname);
00053         bool LoadXML(const char* fname);
00054 
00055 public:
00056     // The marker information is stored in all three tables using 
00057         // the indices-order given in constructor. 
00058         // One idea is that the same 'pointcloud' could contain feature 
00059         // points after marker-corner-points. This way they would be
00060         // optimized simultaneously with marker corners...
00061         std::map<int, CvPoint3D64f> pointcloud;
00062         std::vector<int> marker_indices; // The marker id's to be used in marker field (first being the base)
00063         std::vector<int> marker_status;  // 0: not in point cloud, 1: in point cloud, 2: used in GetPose()
00064         std::vector< std::vector<btVector3> > rel_corners; //The coords of the master marker relative to each child marker in marker_indices
00065 
00066         int pointcloud_index(int marker_id, int marker_corner, bool add_if_missing=false);
00067         int get_id_index(int id, bool add_if_missing=false);
00068 
00069         double _GetPose(MarkerIterator &begin, MarkerIterator &end, Camera* cam, Pose& pose, IplImage* image);
00070 
00071         int _SetTrackMarkers(MarkerDetectorImpl &marker_detector, Camera* cam, Pose& pose, IplImage *image);
00072         int master_id;  //The id of the first marker specified in the XML file 
00073 
00074 
00076         virtual void Reset();
00077 
00082         bool Save(const char* fname, FILE_FORMAT format = FILE_FORMAT_DEFAULT);
00083 
00088         bool Load(const char* fname, FILE_FORMAT format = FILE_FORMAT_DEFAULT);
00089 
00093         MultiMarker(std::vector<int>& indices);
00094 
00096         MultiMarker() {}
00097 
00106         template <class M>
00107         double GetPose(const std::vector<M>* markers, Camera* cam, Pose& pose, IplImage* image = 0)
00108         {
00109                 MarkerIteratorImpl<M> begin(markers->begin());
00110                 MarkerIteratorImpl<M> end(markers->end());
00111                 return _GetPose(begin, end,
00112                                                 cam, pose, image);
00113         }
00114 
00117         template <class M>
00118         double Update(const std::vector<M>* markers, Camera* cam, Pose& pose, IplImage* image = 0)
00119         {
00120                 if(markers->size() < 1) return -1.0;
00121 
00122                 return GetPose(markers, cam, pose, image);
00123         }
00124 
00127         void PointCloudReset();
00128 
00135         void PointCloudCorners3d(double edge_length, Pose &pose, CvPoint3D64f corners[4]);
00136 
00142         void PointCloudAdd(int marker_id, double edge_length, Pose &pose);
00143 
00146         void PointCloudCopy(const MultiMarker *m);
00147 
00150         bool PointCloudIsEmpty() {
00151                 return pointcloud.empty();
00152         }
00153 
00155         size_t Size() {
00156                 return marker_indices.size();
00157         }
00158 
00166         void PointCloudGet(int marker_id, int point,
00167         double &x, double &y, double &z);
00168 
00172         bool IsValidMarker(int marker_id);
00173 
00174         std::vector<int> getIndices(){
00175                 return marker_indices;
00176         }
00177 
00178         int getMasterId(){
00179                 return master_id;
00180         }
00181 
00188         template <class M>
00189         int SetTrackMarkers(MarkerDetector<M> &marker_detector, Camera* cam, Pose& pose, IplImage *image=0) {
00190     return _SetTrackMarkers(marker_detector, cam, pose, image);
00191         }
00192 };
00193 
00194 } // namespace alvar
00195 
00196 #endif


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Sun Oct 5 2014 22:16:26