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

Optimizes all poses in fixed distance from a given vertex and all landmarks that are visible from the optimized poses. More...

#include <graph_opt.h>

Inheritance diagram for vslam::G2OConstActiveDistanceBuilder< G >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Instance
 Maintains state of g2o graph building. It is destroyed ater the graph is built. More...
class  PoseAgeCompare
 Defines ordering on graph verticies given by vertex addition time. More...

Public Member Functions

 G2OConstActiveDistanceBuilder (int _first_landmark_id, double _max_error, int _active_window)

Protected Types

typedef graph_traits< G >
::vertex_descriptor 
VertexD
typedef graph_traits< G >
::vertex_iterator 
VertexItT

Protected Attributes

const int active_window
 see description of this class ( G2OConstActiveDistanceBuilder ).

Private Member Functions

void addLandmarkObservations (int lm_idx, Instance &instance)
 Adds observation constrains for given landmark.
void addPose (VertexD vertex, Instance &instance, bool add_lms)
 Adds pose.
void addVisibleLandmarks (VertexD vertex, Instance &instance)
 Adds landmarks visible from given pose vertex.
virtual void buildGraphImpl (g2o::SparseOptimizer &optimizer, G &g, Points< G > &points, VertexD startv)
void setPoseFixed (VertexD vertex, Instance &instance, bool fixed)
 Sets given pose vertex as fixed. Fixed verticies are not adjusted by the optimalization.

Detailed Description

template<class G>
class vslam::G2OConstActiveDistanceBuilder< G >

Optimizes all poses in fixed distance from a given vertex and all landmarks that are visible from the optimized poses.

Includes all poses that are not further than active_window in the pose-graph as optimalizable. All initialized landmarks visible from added optimizable poses are added into the optimalization. At the time of addition of a new landmark, other poses that the landmark is viewed from are added as non-optimalizable (if they are not added already).

Definition at line 117 of file graph_opt.h.


Member Typedef Documentation

template<class G>
typedef graph_traits<G>::vertex_descriptor vslam::G2OConstActiveDistanceBuilder< G >::VertexD [protected]

Definition at line 120 of file graph_opt.h.

template<class G>
typedef graph_traits<G>::vertex_iterator vslam::G2OConstActiveDistanceBuilder< G >::VertexItT [protected]

Definition at line 119 of file graph_opt.h.


Constructor & Destructor Documentation

template<class G>
vslam::G2OConstActiveDistanceBuilder< G >::G2OConstActiveDistanceBuilder ( int  _first_landmark_id,
double  _max_error,
int  _active_window 
) [inline]
Parameters:
_active_windowsee active_window.

Definition at line 125 of file graph_opt.h.


Member Function Documentation

template<class G>
void vslam::G2OConstActiveDistanceBuilder< G >::addLandmarkObservations ( int  lm_idx,
Instance instance 
) [inline, private]

Adds observation constrains for given landmark.

Poses not present in the graph are added, iff they are not too far from start vertex.

Note:
Issues a ROS warning if observation error is too big. This should not happen because Landmark Manager souhld not allow such landmarks to survive.
Todo:
delete these lms

Definition at line 175 of file graph_opt.h.

template<class G>
void vslam::G2OConstActiveDistanceBuilder< G >::addPose ( VertexD  vertex,
Instance instance,
bool  add_lms 
) [inline, private]

Adds pose.

Parameters:
add_lmsTriggers addition of visible landmarks via addVisibleLandmarks if set true.

Definition at line 247 of file graph_opt.h.

template<class G>
void vslam::G2OConstActiveDistanceBuilder< G >::addVisibleLandmarks ( VertexD  vertex,
Instance instance 
) [inline, private]

Adds landmarks visible from given pose vertex.

Triggers addition of landmark observations via addLandmarkObservations for each observation of given landmark.

Definition at line 220 of file graph_opt.h.

template<class G>
virtual void vslam::G2OConstActiveDistanceBuilder< G >::buildGraphImpl ( g2o::SparseOptimizer &  optimizer,
G &  g,
Points< G > &  points,
VertexD  startv 
) [inline, private, virtual]

Implements vslam::G2OGraphBuilder< G >.

Definition at line 269 of file graph_opt.h.

template<class G>
void vslam::G2OConstActiveDistanceBuilder< G >::setPoseFixed ( VertexD  vertex,
Instance instance,
bool  fixed 
) [inline, private]

Sets given pose vertex as fixed. Fixed verticies are not adjusted by the optimalization.

Definition at line 265 of file graph_opt.h.


Member Data Documentation

template<class G>
const int vslam::G2OConstActiveDistanceBuilder< G >::active_window [protected]

see description of this class ( G2OConstActiveDistanceBuilder ).

Definition at line 122 of file graph_opt.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:16