40 #include <Eigen/StdVector>    52         bool SaveXML(
const char* fname);
    53         bool SaveText(
const char* fname);
    54         bool LoadText(
const char* fname);
    55         bool LoadXML(
const char* fname);
    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);
   113                 return _GetPose(begin, end,
   122                 if(markers->size() < 1) 
return -1.0;
   124                 return GetPose(markers, cam, pose, 
image);
   129         void PointCloudReset();
   137         void PointCloudCorners3d(
double edge_length, 
Pose &pose, CvPoint3D64f corners[4]);
   144         void PointCloudAdd(
int marker_id, 
double edge_length, 
Pose &pose);
   153                 return pointcloud.empty();
   158                 return marker_indices.size();
   168         void PointCloudGet(
int marker_id, 
int point,
   169         double &
x, 
double &
y, 
double &
z);
   174         bool IsValidMarker(
int marker_id);
   177                 return marker_indices;
   192     return _SetTrackMarkers(marker_detector, cam, pose, 
image);
 
size_t Size()
Return the number of markers added using PointCloudAdd. 
This file implements a camera used for projecting points and computing homographies. 
This file implements a generic marker detector. 
std::vector< int > marker_status
This file implements multiple filters. 
Base class for using MultiMarker. 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
Templateless version of MarkerDetector. Please use MarkerDetector instead. 
std::map< int, CvPoint3D64f > pointcloud
std::vector< int > marker_indices
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...
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
bool PointCloudIsEmpty()
Returns true if the are not points in the 3D opint cloud. 
This file implements a parametrized rotation. 
MarkerDetector for detecting markers of type M 
Pose representation derived from the Rotation class 
TFSIMD_FORCE_INLINE const tfScalar & x() const 
MultiMarker()
Default constructor. 
MarkerDetector< MarkerData > marker_detector
TFSIMD_FORCE_INLINE const tfScalar & z() const 
Iterator type for traversing templated Marker vector without the template. 
Iterator implementation for traversing templated Marker vector without the template. 
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 ...
double Update(const std::vector< M, Eigen::aligned_allocator< M > > *markers, Camera *cam, Pose &pose, IplImage *image=0)
Calls GetPose to obtain camera pose. 
This file defines library export definitions, version numbers and build information. 
std::vector< int > getIndices()
std::vector< std::vector< tf::Vector3 > > rel_corners