MultiMarker.h
Go to the documentation of this file.
1 /*
2  * This file is part of ALVAR, A Library for Virtual and Augmented Reality.
3  *
4  * Copyright 2007-2012 VTT Technical Research Centre of Finland
5  *
6  * Contact: VTT Augmented Reality Team <alvar.info@vtt.fi>
7  * <http://www.vtt.fi/multimedia/alvar.html>
8  *
9  * ALVAR is free software; you can redistribute it and/or modify it under the
10  * terms of the GNU Lesser General Public License as published by the Free
11  * Software Foundation; either version 2.1 of the License, or (at your option)
12  * any later version.
13  *
14  * This library is distributed in the hope that it will be useful, but WITHOUT
15  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
16  * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License
17  * for more details.
18  *
19  * You should have received a copy of the GNU Lesser General Public License
20  * along with ALVAR; if not, see
21  * <http://www.gnu.org/licenses/old-licenses/lgpl-2.1.html>.
22  */
23 
24 #ifndef MULTIMARKER_H
25 #define MULTIMARKER_H
26 
33 #include "Alvar.h"
34 #include "Rotation.h"
35 #include "MarkerDetector.h"
36 #include "Camera.h"
37 #include "Filter.h"
38 #include "FileFormat.h"
39 #include <tf/LinearMath/Vector3.h>
40 #include <Eigen/StdVector>
41 
42 namespace alvar {
43 
48 
49 
50 private:
51 
52  bool SaveXML(const char* fname);
53  bool SaveText(const char* fname);
54  bool LoadText(const char* fname);
55  bool LoadXML(const char* fname);
56 
57 public:
58  // The marker information is stored in all three tables using
59  // the indices-order given in constructor.
60  // One idea is that the same 'pointcloud' could contain feature
61  // points after marker-corner-points. This way they would be
62  // optimized simultaneously with marker corners...
63  std::map<int, CvPoint3D64f> pointcloud;
64  std::vector<int> marker_indices; // The marker id's to be used in marker field (first being the base)
65  std::vector<int> marker_status; // 0: not in point cloud, 1: in point cloud, 2: used in GetPose()
66  std::vector< std::vector<tf::Vector3> > rel_corners; //The coords of the master marker relative to each child marker in marker_indices
67 
68  int pointcloud_index(int marker_id, int marker_corner, bool add_if_missing=false);
69  int get_id_index(int id, bool add_if_missing=false);
70 
71  double _GetPose(MarkerIterator &begin, MarkerIterator &end, Camera* cam, Pose& pose, IplImage* image);
72 
73  int _SetTrackMarkers(MarkerDetectorImpl &marker_detector, Camera* cam, Pose& pose, IplImage *image);
74  int master_id; //The id of the first marker specified in the XML file
75 
76 
78  virtual void Reset();
79 
84  bool Save(const char* fname, FILE_FORMAT format = FILE_FORMAT_DEFAULT);
85 
90  bool Load(const char* fname, FILE_FORMAT format = FILE_FORMAT_DEFAULT);
91 
95  MultiMarker(std::vector<int>& indices);
96 
99 
108  template <class M>
109  double GetPose(const std::vector<M, Eigen::aligned_allocator<M> >* markers, Camera* cam, Pose& pose, IplImage* image = 0)
110  {
111  MarkerIteratorImpl<M> begin(markers->begin());
112  MarkerIteratorImpl<M> end(markers->end());
113  return _GetPose(begin, end,
114  cam, pose, image);
115  }
116 
119  template <class M>
120  double Update(const std::vector<M, Eigen::aligned_allocator<M> >* markers, Camera* cam, Pose& pose, IplImage* image = 0)
121  {
122  if(markers->size() < 1) return -1.0;
123 
124  return GetPose(markers, cam, pose, image);
125  }
126 
129  void PointCloudReset();
130 
137  void PointCloudCorners3d(double edge_length, Pose &pose, CvPoint3D64f corners[4]);
138 
144  void PointCloudAdd(int marker_id, double edge_length, Pose &pose);
145 
148  void PointCloudCopy(const MultiMarker *m);
149 
153  return pointcloud.empty();
154  }
155 
157  size_t Size() {
158  return marker_indices.size();
159  }
160 
168  void PointCloudGet(int marker_id, int point,
169  double &x, double &y, double &z);
170 
174  bool IsValidMarker(int marker_id);
175 
176  std::vector<int> getIndices(){
177  return marker_indices;
178  }
179 
180  int getMasterId(){
181  return master_id;
182  }
183 
190  template <class M>
192  return _SetTrackMarkers(marker_detector, cam, pose, image);
193  }
194 };
195 
196 } // namespace alvar
197 
198 #endif
Main ALVAR namespace.
Definition: Alvar.h:174
Default file format.
Definition: FileFormat.h:45
size_t Size()
Return the number of markers added using PointCloudAdd.
Definition: MultiMarker.h:157
This file implements a camera used for projecting points and computing homographies.
This file implements a generic marker detector.
std::vector< int > marker_status
Definition: MultiMarker.h:65
unsigned char * image
Definition: GlutViewer.cpp:155
This file implements multiple filters.
int * master_id
Base class for using MultiMarker.
Definition: MultiMarker.h:47
TFSIMD_FORCE_INLINE const tfScalar & y() const
Templateless version of MarkerDetector. Please use MarkerDetector instead.
std::map< int, CvPoint3D64f > pointcloud
Definition: MultiMarker.h:63
std::vector< int > marker_indices
Definition: MultiMarker.h:64
double GetPose(const std::vector< M, Eigen::aligned_allocator< M > > *markers, Camera *cam, Pose &pose, IplImage *image=0)
Calculates the pose of the camera from multi marker. Method uses the true 3D coordinates of markers t...
Definition: MultiMarker.h:109
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
Definition: Camera.h:82
bool PointCloudIsEmpty()
Returns true if the are not points in the 3D opint cloud.
Definition: MultiMarker.h:152
This file implements a parametrized rotation.
MarkerDetector for detecting markers of type M
FILE_FORMAT
Definition: FileFormat.h:39
Pose representation derived from the Rotation class
Definition: Pose.h:50
TFSIMD_FORCE_INLINE const tfScalar & x() const
MultiMarker()
Default constructor.
Definition: MultiMarker.h:98
MarkerDetector< MarkerData > marker_detector
This file defines various file formats.
TFSIMD_FORCE_INLINE const tfScalar & z() const
Iterator type for traversing templated Marker vector without the template.
Definition: Marker.h:277
#define ALVAR_EXPORT
Definition: Alvar.h:168
Iterator implementation for traversing templated Marker vector without the template.
Definition: Marker.h:294
Camera * cam
int SetTrackMarkers(MarkerDetector< M > &marker_detector, Camera *cam, Pose &pose, IplImage *image=0)
Set new markers to be tracked for MarkerDetector Sometimes the MultiMarker implementation knows more ...
Definition: MultiMarker.h:191
double Update(const std::vector< M, Eigen::aligned_allocator< M > > *markers, Camera *cam, Pose &pose, IplImage *image=0)
Calls GetPose to obtain camera pose.
Definition: MultiMarker.h:120
This file defines library export definitions, version numbers and build information.
std::vector< int > getIndices()
Definition: MultiMarker.h:176
std::vector< std::vector< tf::Vector3 > > rel_corners
Definition: MultiMarker.h:66


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Mon Jun 10 2019 12:47:04