Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
alvar::MultiMarkerFiltered Class Reference

Multi marker that is constructed by first calculating the marker poses directly relative to base marker and then filtering the results using e.g. median filter. More...

#include <MultiMarkerFiltered.h>

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

Public Member Functions

void MeasurementsReset ()
 Reset the measurements. More...
 
 MultiMarkerFiltered (std::vector< int > &indices)
 Constructor. More...
 
void PointCloudAverage (int marker_id, double edge_length, Pose &pose)
 Updates the 3D point cloud by averaging the calculated results. More...
 
template<class M >
double Update (const std::vector< M > *markers, Camera *cam, Pose &pose, IplImage *image=0)
 Updates the marker field and camera pose. More...
 
 ~MultiMarkerFiltered ()
 Destructor. More...
 
- 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 Member Functions

double _Update (MarkerIterator &begin, MarkerIterator &end, Camera *cam, Pose &pose, IplImage *image)
 

Protected Attributes

FilterMedianpointcloud_filtered
 

Static Protected Attributes

static const int filter_buffer_max =15
 

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

Multi marker that is constructed by first calculating the marker poses directly relative to base marker and then filtering the results using e.g. median filter.

This can be used to initialize the marker field for MultiMarkerBundle class.

Definition at line 45 of file MultiMarkerFiltered.h.

Constructor & Destructor Documentation

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

Constructor.

Parameters
indicesVector of marker codes that are included into multi marker. The first element defines origin.

Definition at line 31 of file MultiMarkerFiltered.cpp.

alvar::MultiMarkerFiltered::~MultiMarkerFiltered ( )

Destructor.

Definition at line 40 of file MultiMarkerFiltered.cpp.

Member Function Documentation

double alvar::MultiMarkerFiltered::_Update ( MarkerIterator begin,
MarkerIterator end,
Camera cam,
Pose pose,
IplImage *  image 
)
protected

Definition at line 68 of file MultiMarkerFiltered.cpp.

void alvar::MultiMarkerFiltered::MeasurementsReset ( )
inline

Reset the measurements.

Definition at line 89 of file MultiMarkerFiltered.h.

void alvar::MultiMarkerFiltered::PointCloudAverage ( int  marker_id,
double  edge_length,
Pose pose 
)

Updates the 3D point cloud by averaging the calculated results.

Parameters
marker_idThe id of the marker whose corner positions are updated.
edge_lengthThe edge length of the marker.
poseCurrent camera pose that is used to estimate the marker position.

Definition at line 45 of file MultiMarkerFiltered.cpp.

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

Updates the marker field and camera pose.

Parameters
markersMarkers seen by the camera.
cameraCamera object used to detect markers.
poseCurrent camera pose. This is also updated.
imageIf != 0 some visualization will be drawn.

Definition at line 77 of file MultiMarkerFiltered.h.

Member Data Documentation

const int alvar::MultiMarkerFiltered::filter_buffer_max =15
staticprotected

Definition at line 48 of file MultiMarkerFiltered.h.

FilterMedian* alvar::MultiMarkerFiltered::pointcloud_filtered
protected

Definition at line 49 of file MultiMarkerFiltered.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