Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
alvar::MultiMarkerInitializer Class Reference

Initializes multi marker by estimating their relative positions from one or more images. More...

#include <MultiMarkerInitializer.h>

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

Classes

class  MarkerMeasurement
 MarkerMeasurement that holds the maker id. More...
 

Public Member Functions

int getMeasurementCount ()
 
const std::vector< MarkerMeasurement, Eigen::aligned_allocator< MarkerMeasurement > > & getMeasurementMarkers (int measurement)
 
double getMeasurementPose (int measurement, Camera *cam, Pose &pose)
 
int Initialize (Camera *cam)
 
template<class M >
void MeasurementsAdd (const std::vector< M, Eigen::aligned_allocator< M > > *markers)
 
void MeasurementsReset ()
 
 MultiMarkerInitializer (std::vector< int > &indices, int filter_buffer_min=4, int filter_buffer_max=15)
 
 ~MultiMarkerInitializer ()
 
- Public Member Functions inherited from alvar::MultiMarker
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...
 

Protected Types

typedef std::vector< std::vector< MarkerMeasurement, Eigen::aligned_allocator< MarkerMeasurement > > >::iterator MeasurementIterator
 

Protected Member Functions

void MeasurementsAdd (MarkerIterator &begin, MarkerIterator &end)
 
bool updateMarkerPoses (std::vector< MarkerMeasurement, Eigen::aligned_allocator< MarkerMeasurement > > &markers, const Pose &pose)
 

Protected Attributes

int filter_buffer_min
 
std::vector< bool > marker_detected
 
std::vector< std::vector< MarkerMeasurement, Eigen::aligned_allocator< MarkerMeasurement > > > measurements
 
FilterMedianpointcloud_filtered
 

Additional Inherited Members

- Public Attributes inherited from alvar::MultiMarker
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
 

Detailed Description

Initializes multi marker by estimating their relative positions from one or more images.

To use, detect markers from images using MarkerDetector and call addMeasurement for each image that has at least two markers. Finally, call initialize to compute the relative positions of markers.

After the multi marker has been initialized, the point cloud can be copied into another MultiMarker implementation by PointCloudCopy.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 50 of file MultiMarkerInitializer.h.

Member Typedef Documentation

typedef std::vector<std::vector<MarkerMeasurement, Eigen::aligned_allocator<MarkerMeasurement> > >::iterator alvar::MultiMarkerInitializer::MeasurementIterator
protected

Definition at line 68 of file MultiMarkerInitializer.h.

Constructor & Destructor Documentation

alvar::MultiMarkerInitializer::MultiMarkerInitializer ( std::vector< int > &  indices,
int  filter_buffer_min = 4,
int  filter_buffer_max = 15 
)

Definition at line 32 of file MultiMarkerInitializer.cpp.

alvar::MultiMarkerInitializer::~MultiMarkerInitializer ( )

Member Function Documentation

int alvar::MultiMarkerInitializer::getMeasurementCount ( )
inline
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 113 of file MultiMarkerInitializer.h.

const std::vector<MarkerMeasurement, Eigen::aligned_allocator<MarkerMeasurement> >& alvar::MultiMarkerInitializer::getMeasurementMarkers ( int  measurement)
inline
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 115 of file MultiMarkerInitializer.h.

double alvar::MultiMarkerInitializer::getMeasurementPose ( int  measurement,
Camera cam,
Pose pose 
)
inline
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 119 of file MultiMarkerInitializer.h.

int alvar::MultiMarkerInitializer::Initialize ( Camera cam)

Tries to deduce marker poses from measurements.

Returns the number of initialized markers.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 94 of file MultiMarkerInitializer.cpp.

void alvar::MultiMarkerInitializer::MeasurementsAdd ( MarkerIterator begin,
MarkerIterator end 
)
protected
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 44 of file MultiMarkerInitializer.cpp.

template<class M >
void alvar::MultiMarkerInitializer::MeasurementsAdd ( const std::vector< M, Eigen::aligned_allocator< M > > *  markers)
inline

Adds a new measurement for marker field initialization. Each measurement should contain at least two markers. It does not matter which markers are visible, especially the zero marker does not have to be visible in every measurement. It suffices that there exists a 'path' from the zero marker to every other marker in the marker field.

For example:

  • first measurement contains marker A and B.
  • second measurement containt markers ZERO and A.

When Initialize is called, the system can first deduce the pose of A and then the pose of B.

Definition at line 95 of file MultiMarkerInitializer.h.

void alvar::MultiMarkerInitializer::MeasurementsReset ( )
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 83 of file MultiMarkerInitializer.cpp.

bool alvar::MultiMarkerInitializer::updateMarkerPoses ( std::vector< MarkerMeasurement, Eigen::aligned_allocator< MarkerMeasurement > > &  markers,
const Pose pose 
)
protected

Definition at line 120 of file MultiMarkerInitializer.cpp.

Member Data Documentation

int alvar::MultiMarkerInitializer::filter_buffer_min
protected

Definition at line 70 of file MultiMarkerInitializer.h.

std::vector<bool> alvar::MultiMarkerInitializer::marker_detected
protected

Definition at line 66 of file MultiMarkerInitializer.h.

std::vector<std::vector<MarkerMeasurement, Eigen::aligned_allocator<MarkerMeasurement> > > alvar::MultiMarkerInitializer::measurements
protected

Definition at line 67 of file MultiMarkerInitializer.h.

FilterMedian* alvar::MultiMarkerInitializer::pointcloud_filtered
protected

Definition at line 69 of file MultiMarkerInitializer.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