Public Member Functions | Public Attributes | Private Member Functions | List of all members
alvar::MultiMarker Class Reference

Base class for using MultiMarker. More...

#include <MultiMarker.h>

Inheritance diagram for alvar::MultiMarker:
Inheritance graph
[legend]

Public Member Functions

double _GetPose (MarkerIterator &begin, MarkerIterator &end, Camera *cam, Pose &pose, IplImage *image)
 
int _SetTrackMarkers (MarkerDetectorImpl &marker_detector, Camera *cam, Pose &pose, IplImage *image)
 
int get_id_index (int id, bool add_if_missing=false)
 
std::vector< int > getIndices ()
 
int getMasterId ()
 
template<class M >
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 to get the initial pose and then optimizes it by minimizing the reprojection error. More...
 
bool IsValidMarker (int marker_id)
 Returns true if the marker is in the point cloud. More...
 
bool Load (const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
 Loads multi marker configuration from a text file. More...
 
 MultiMarker (std::vector< int > &indices)
 Constructor. More...
 
 MultiMarker ()
 Default constructor. More...
 
int pointcloud_index (int marker_id, int marker_corner, bool add_if_missing=false)
 
void PointCloudAdd (int marker_id, double edge_length, Pose &pose)
 Adds marker corners to 3D point cloud of multi marker. More...
 
void PointCloudCopy (const MultiMarker *m)
 Copies the 3D point cloud from other multi marker object. More...
 
void PointCloudCorners3d (double edge_length, Pose &pose, CvPoint3D64f corners[4])
 Calculates 3D coordinates of marker corners relative to given pose (camera). More...
 
void PointCloudGet (int marker_id, int point, double &x, double &y, double &z)
 Returns 3D co-ordinates of one corner point of a marker. More...
 
bool PointCloudIsEmpty ()
 Returns true if the are not points in the 3D opint cloud. More...
 
void PointCloudReset ()
 Reserts the 3D point cloud of the markers. More...
 
virtual void Reset ()
 Resets the multi marker. More...
 
bool Save (const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
 Saves multi marker configuration to a text file. More...
 
template<class M >
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 about marker locations compared to MarkerDetector . Then this method can be used to reset the internal state of MarkerDetector for tracking also these markers. More...
 
size_t Size ()
 Return the number of markers added using PointCloudAdd. More...
 
template<class M >
double Update (const std::vector< M, Eigen::aligned_allocator< M > > *markers, Camera *cam, Pose &pose, IplImage *image=0)
 Calls GetPose to obtain camera pose. More...
 

Public Attributes

std::vector< int > marker_indices
 
std::vector< int > marker_status
 
int master_id
 
std::map< int, CvPoint3D64f > pointcloud
 
std::vector< std::vector< tf::Vector3 > > rel_corners
 

Private Member Functions

bool LoadText (const char *fname)
 
bool LoadXML (const char *fname)
 
bool SaveText (const char *fname)
 
bool SaveXML (const char *fname)
 

Detailed Description

Base class for using MultiMarker.

Examples:
SampleMarkerCreator.cpp, and SampleMultiMarker.cpp.

Definition at line 47 of file MultiMarker.h.

Constructor & Destructor Documentation

alvar::MultiMarker::MultiMarker ( std::vector< int > &  indices)

Constructor.

Parameters
indicesVector of marker codes that are included into multi marker. The first element defines origin.
alvar::MultiMarker::MultiMarker ( )
inline

Default constructor.

Definition at line 98 of file MultiMarker.h.

Member Function Documentation

double alvar::MultiMarker::_GetPose ( MarkerIterator begin,
MarkerIterator end,
Camera cam,
Pose pose,
IplImage *  image 
)

Definition at line 296 of file MultiMarker.cpp.

int alvar::MultiMarker::_SetTrackMarkers ( MarkerDetectorImpl marker_detector,
Camera cam,
Pose pose,
IplImage *  image 
)

Definition at line 339 of file MultiMarker.cpp.

int alvar::MultiMarker::get_id_index ( int  id,
bool  add_if_missing = false 
)

Definition at line 38 of file MultiMarker.cpp.

std::vector<int> alvar::MultiMarker::getIndices ( )
inline

Definition at line 176 of file MultiMarker.h.

int alvar::MultiMarker::getMasterId ( )
inline

Definition at line 180 of file MultiMarker.h.

template<class M >
double alvar::MultiMarker::GetPose ( const std::vector< M, Eigen::aligned_allocator< M > > *  markers,
Camera cam,
Pose pose,
IplImage *  image = 0 
)
inline

Calculates the pose of the camera from multi marker. Method uses the true 3D coordinates of markers to get the initial pose and then optimizes it by minimizing the reprojection error.

Parameters
markersVector of markers seen by camera.
camCamera object containing internal calibration etc.
poseThe resulting pose is stored here.
imageIf != 0 some visualizations are drawn.

Definition at line 109 of file MultiMarker.h.

bool alvar::MultiMarker::IsValidMarker ( int  marker_id)

Returns true if the marker is in the point cloud.

Parameters
marker_idID of the marker.

Definition at line 290 of file MultiMarker.cpp.

bool alvar::MultiMarker::Load ( const char *  fname,
FILE_FORMAT  format = FILE_FORMAT_DEFAULT 
)

Loads multi marker configuration from a text file.

Parameters
fnamefile name
formatFILE_FORMAT_TEXT (default) or FILE_FORMAT_XML (see doc/MultiMarker.xsd).
Examples:
SampleMultiMarker.cpp, and SampleMultiMarkerBundle.cpp.

Definition at line 205 of file MultiMarker.cpp.

bool alvar::MultiMarker::LoadText ( const char *  fname)
private

Definition at line 168 of file MultiMarker.cpp.

bool alvar::MultiMarker::LoadXML ( const char *  fname)
private

Definition at line 127 of file MultiMarker.cpp.

int alvar::MultiMarker::pointcloud_index ( int  marker_id,
int  marker_corner,
bool  add_if_missing = false 
)

Definition at line 34 of file MultiMarker.cpp.

void alvar::MultiMarker::PointCloudAdd ( int  marker_id,
double  edge_length,
Pose pose 
)

Adds marker corners to 3D point cloud of multi marker.

Parameters
marker_idId of the marker to be added.
edge_lengthEdge length of the marker.
poseCurrent camera pose.
Examples:
SampleMarkerCreator.cpp, SampleMultiMarker.cpp, and SampleMultiMarkerBundle.cpp.

Definition at line 264 of file MultiMarker.cpp.

void alvar::MultiMarker::PointCloudCopy ( const MultiMarker m)

Copies the 3D point cloud from other multi marker object.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 273 of file MultiMarker.cpp.

void alvar::MultiMarker::PointCloudCorners3d ( double  edge_length,
Pose pose,
CvPoint3D64f  corners[4] 
)

Calculates 3D coordinates of marker corners relative to given pose (camera).

Parameters
edge_lengthThe edge length of the marker.
poseCurrent pose of the camera.
cornersResulted 3D corner points are stored here.

Definition at line 229 of file MultiMarker.cpp.

void alvar::MultiMarker::PointCloudGet ( int  marker_id,
int  point,
double &  x,
double &  y,
double &  z 
)

Returns 3D co-ordinates of one corner point of a marker.

Parameters
marker_idID of the marker which corner point is returned.
pointNumber of the corner point to return, from 0 to 3.
xx co-ordinate is returned.
yy co-ordinate is returned.
zz co-ordinate is returned.

Definition at line 282 of file MultiMarker.cpp.

bool alvar::MultiMarker::PointCloudIsEmpty ( )
inline

Returns true if the are not points in the 3D opint cloud.

Definition at line 152 of file MultiMarker.h.

void alvar::MultiMarker::PointCloudReset ( )

Reserts the 3D point cloud of the markers.

Definition at line 225 of file MultiMarker.cpp.

void alvar::MultiMarker::Reset ( )
virtual

Resets the multi marker.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 50 of file MultiMarker.cpp.

bool alvar::MultiMarker::Save ( const char *  fname,
FILE_FORMAT  format = FILE_FORMAT_DEFAULT 
)

Saves multi marker configuration to a text file.

Parameters
fnamefile name
formatFILE_FORMAT_TEXT (default) or FILE_FORMAT_XML (see doc/MultiMarker.xsd).
Examples:
SampleMarkerCreator.cpp, and SampleMultiMarkerBundle.cpp.

Definition at line 115 of file MultiMarker.cpp.

bool alvar::MultiMarker::SaveText ( const char *  fname)
private

Definition at line 84 of file MultiMarker.cpp.

bool alvar::MultiMarker::SaveXML ( const char *  fname)
private

Definition at line 56 of file MultiMarker.cpp.

template<class M >
int alvar::MultiMarker::SetTrackMarkers ( MarkerDetector< M > &  marker_detector,
Camera cam,
Pose pose,
IplImage *  image = 0 
)
inline

Set new markers to be tracked for MarkerDetector Sometimes the MultiMarker implementation knows more about marker locations compared to MarkerDetector . Then this method can be used to reset the internal state of MarkerDetector for tracking also these markers.

Examples:
SampleMultiMarker.cpp, and SampleMultiMarkerBundle.cpp.

Definition at line 191 of file MultiMarker.h.

size_t alvar::MultiMarker::Size ( )
inline

Return the number of markers added using PointCloudAdd.

Examples:
SampleMarkerCreator.cpp.

Definition at line 157 of file MultiMarker.h.

template<class M >
double alvar::MultiMarker::Update ( const std::vector< M, Eigen::aligned_allocator< M > > *  markers,
Camera cam,
Pose pose,
IplImage *  image = 0 
)
inline

Calls GetPose to obtain camera pose.

Examples:
SampleMultiMarker.cpp, and SampleMultiMarkerBundle.cpp.

Definition at line 120 of file MultiMarker.h.

Member Data Documentation

std::vector<int> alvar::MultiMarker::marker_indices

Definition at line 64 of file MultiMarker.h.

std::vector<int> alvar::MultiMarker::marker_status

Definition at line 65 of file MultiMarker.h.

int alvar::MultiMarker::master_id

Definition at line 74 of file MultiMarker.h.

std::map<int, CvPoint3D64f> alvar::MultiMarker::pointcloud

Definition at line 63 of file MultiMarker.h.

std::vector< std::vector<tf::Vector3> > alvar::MultiMarker::rel_corners

Definition at line 66 of file MultiMarker.h.


The documentation for this class was generated from the following files:


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 19:27:24