All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines
Public Member Functions | Protected Types | Protected Attributes
vslam::lmdetails::PointsLoc< G > Class Template Reference

holds all landmarks in the scene. Helps managing landmarks. More...

#include <landmark_manager.h>

List of all members.

Public Member Functions

void addObservation (const G &g, int idx, FeatureID< G > &f, const Vector3d &estimate)
 Add observation to a landmark.
int create (const G &g, const vector< FeatureID< G > > &observations, const Vector3d &estimate)
 Creates a new landmark with given features as observations and `estimate` as its position.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
void 
destroy (int idx, G &g)
Point< G > & getPoint (int idx)
const Point< G > & getPoint (int idx) const
int size () const

Protected Types

typedef graph_traits< G >
::vertex_descriptor 
VertexD

Protected Attributes

vector< Point< G > > pts

Detailed Description

template<typename G>
class vslam::lmdetails::PointsLoc< G >

holds all landmarks in the scene. Helps managing landmarks.

Definition at line 75 of file landmark_manager.h.


Member Typedef Documentation

template<typename G>
typedef graph_traits<G>::vertex_descriptor vslam::lmdetails::PointsLoc< G >::VertexD [protected]

Definition at line 78 of file landmark_manager.h.


Member Function Documentation

template<typename G>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void vslam::lmdetails::PointsLoc< G >::destroy ( int  idx,
G &  g 
) [inline]

Definition at line 82 of file landmark_manager.h.

template<typename G>
Point<G>& vslam::lmdetails::PointsLoc< G >::getPoint ( int  idx) [inline]

Definition at line 98 of file landmark_manager.h.

template<typename G>
const Point<G>& vslam::lmdetails::PointsLoc< G >::getPoint ( int  idx) const [inline]

Definition at line 102 of file landmark_manager.h.

template<typename G>
int vslam::lmdetails::PointsLoc< G >::size ( ) const [inline]

Definition at line 106 of file landmark_manager.h.


Member Data Documentation

template<typename G>
vector<Point<G> > vslam::lmdetails::PointsLoc< G >::pts [protected]

Definition at line 77 of file landmark_manager.h.


The documentation for this class was generated from the following file:
 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:17