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

Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud). More...

#include <MultiMarkerBundle.h>

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

Public Member Functions

double GetOptimizationError ()
 
int GetOptimizationKeyframes ()
 
int GetOptimizationMarkers ()
 
bool GetOptimizing ()
 
template<class M >
void MeasurementsAdd (const std::vector< M, Eigen::aligned_allocator< M > > *markers, const Pose &camera_pose)
 Adds new measurements that are used in bundle adjustment. More...
 
void MeasurementsReset ()
 Resets the measurements and camera poses that are stored for bundle adjustment. If something goes from in optimization one will call this and acquire new measurements. More...
 
 MultiMarkerBundle (std::vector< int > &indices)
 Constructor. More...
 
bool Optimize (Camera *_cam, double stop, int max_iter, Optimization::OptimizeMethod method=Optimization::TUKEY_LM)
 Runs the bundle adjustment optimization. More...
 
 ~MultiMarkerBundle ()
 
- 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

void _MeasurementsAdd (MarkerIterator &begin, MarkerIterator &end, const Pose &camera_pose)
 
int measurements_index (int frame, int marker_id, int marker_corner)
 

Protected Attributes

std::vector< Posecamera_poses
 
std::map< int, PointDoublemeasurements
 
double optimization_error
 
int optimization_keyframes
 
int optimization_markers
 
bool optimizing
 

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 uses bundle adjustment to refine the 3D positions of the markers (point cloud).

This can be initialized by using e.g. MultiMarkerAverage class.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 45 of file MultiMarkerBundle.h.

Constructor & Destructor Documentation

alvar::MultiMarkerBundle::MultiMarkerBundle ( 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 MultiMarkerBundle.cpp.

alvar::MultiMarkerBundle::~MultiMarkerBundle ( )

Definition at line 37 of file MultiMarkerBundle.cpp.

Member Function Documentation

void alvar::MultiMarkerBundle::_MeasurementsAdd ( MarkerIterator begin,
MarkerIterator end,
const Pose camera_pose 
)
protected

Definition at line 253 of file MultiMarkerBundle.cpp.

double alvar::MultiMarkerBundle::GetOptimizationError ( )
inline

Definition at line 75 of file MultiMarkerBundle.h.

int alvar::MultiMarkerBundle::GetOptimizationKeyframes ( )
inline

Definition at line 76 of file MultiMarkerBundle.h.

int alvar::MultiMarkerBundle::GetOptimizationMarkers ( )
inline

Definition at line 77 of file MultiMarkerBundle.h.

bool alvar::MultiMarkerBundle::GetOptimizing ( )
inline

Definition at line 78 of file MultiMarkerBundle.h.

int alvar::MultiMarkerBundle::measurements_index ( int  frame,
int  marker_id,
int  marker_corner 
)
inlineprotected

Definition at line 54 of file MultiMarkerBundle.h.

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

Adds new measurements that are used in bundle adjustment.

Parameters
markersVector of markers detected by MarkerDetector.
camera_poseCurrent camera pose.
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 85 of file MultiMarkerBundle.h.

void alvar::MultiMarkerBundle::MeasurementsReset ( )

Resets the measurements and camera poses that are stored for bundle adjustment. If something goes from in optimization one will call this and acquire new measurements.

Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 41 of file MultiMarkerBundle.cpp.

bool alvar::MultiMarkerBundle::Optimize ( Camera _cam,
double  stop,
int  max_iter,
Optimization::OptimizeMethod  method = Optimization::TUKEY_LM 
)

Runs the bundle adjustment optimization.

Parameters
markersVector of markers detected by MarkerDetector.
camera_poseCurrent camera pose.
max_iterMaximum number of iteration loops.
methodThe method that is applied inside optimization. Try Optimization::LEVENBERGMARQUARDT or Optimization::GAUSSNEWTON or Optmization::TUKEY_LM
Examples:
SampleMultiMarkerBundle.cpp.

Definition at line 102 of file MultiMarkerBundle.cpp.

Member Data Documentation

std::vector<Pose> alvar::MultiMarkerBundle::camera_poses
protected

Definition at line 52 of file MultiMarkerBundle.h.

std::map<int, PointDouble> alvar::MultiMarkerBundle::measurements
protected

Definition at line 53 of file MultiMarkerBundle.h.

double alvar::MultiMarkerBundle::optimization_error
protected

Definition at line 50 of file MultiMarkerBundle.h.

int alvar::MultiMarkerBundle::optimization_keyframes
protected

Definition at line 48 of file MultiMarkerBundle.h.

int alvar::MultiMarkerBundle::optimization_markers
protected

Definition at line 49 of file MultiMarkerBundle.h.

bool alvar::MultiMarkerBundle::optimizing
protected

Definition at line 51 of file MultiMarkerBundle.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