Classes | Functions
Landmark Activation and Pruning
Implementation
Collaboration diagram for Landmark Activation and Pruning:

Classes

class  vslam::lmdetails::DisparityLmOrdering< G >
 Defines total ordering of landmarks based on disparity. More...
class  vslam::lmdetails::LandmarkQualityOrdering< G >

Functions

template<class G >
double vslam::lmdetails::ftrTrackEndToEndDisparity (const G &g, const Point< G > &pt)
 Computes disparity of features from the first sighting to the last sighting.
template<class G >
void vslam::lmdetails::pruneLandmarks (const G &g, PointsLoc< G > &points, typename graph_traits< G >::vertex_descriptor v, int keep_num)

Function Documentation

template<class G >
double vslam::lmdetails::ftrTrackEndToEndDisparity ( const G &  g,
const Point< G > &  pt 
)

Computes disparity of features from the first sighting to the last sighting.

Definition at line 188 of file landmark_manager.h.

template<class G >
void vslam::lmdetails::pruneLandmarks ( const G &  g,
PointsLoc< G > &  points,
typename graph_traits< G >::vertex_descriptor  v,
int  keep_num 
)

Definition at line 223 of file landmark_manager.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pose_estimation
Author(s): Jiri Divis/jiridivis@gmail.com
autogenerated on Wed Mar 27 2013 21:00:14