Keyframe manager based on covisibility (i.e. number of matched features) between keyframes. More...
#include <vo.h>
Public Member Functions | |
virtual bool | buildNewKeyframe () |
decides if current frame should be keyframe. | |
CovisibilityKeyframeVisualOdometry (shared_ptr< NodeBuilderTT< PoseGraphT > > _nbuilder, shared_ptr< EdgeBuilder< PoseGraphT > > _ebuilder, double _ctreshold=0.8, size_t _target_past_verticies_size=1, shared_ptr< VodomLogger< PoseGraphT > > _logger=shared_ptr< VodomLogger< PoseGraphT > >()) | |
int | getEdgeCovisibility (VertexD s, VertexD t) |
virtual void | newKeyframeBuilt () |
stuff that needs to be done after creating new keyframe. | |
Protected Types | |
typedef graph_traits < PoseGraphT > ::vertex_descriptor | VertexD |
Protected Attributes | |
double | ctreshold |
multiplier as described in the constructor | |
double | minimum |
covisibility for the first edge as described in the constuctor |
Keyframe manager based on covisibility (i.e. number of matched features) between keyframes.
typedef graph_traits<PoseGraphT>::vertex_descriptor vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::VertexD [protected] |
Reimplemented from vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.
vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::CovisibilityKeyframeVisualOdometry | ( | shared_ptr< NodeBuilderTT< PoseGraphT > > | _nbuilder, |
shared_ptr< EdgeBuilder< PoseGraphT > > | _ebuilder, | ||
double | _ctreshold = 0.8 , |
||
size_t | _target_past_verticies_size = 1 , |
||
shared_ptr< VodomLogger< PoseGraphT > > | _logger = shared_ptr<VodomLogger<PoseGraphT> >() |
||
) | [inline] |
_cthreshold | multiplier of the covisibility between last keyframe and first edge that was added with it as vertex after it was designated as keyframe. if the covisibility of last added edge drops bellow the _cthreshold * covisibility, new keyframe is created. |
virtual bool vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::buildNewKeyframe | ( | ) | [inline, virtual] |
decides if current frame should be keyframe.
Implements vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.
int vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::getEdgeCovisibility | ( | VertexD | s, |
VertexD | t | ||
) | [inline] |
virtual void vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::newKeyframeBuilt | ( | ) | [inline, virtual] |
stuff that needs to be done after creating new keyframe.
Implements vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.
double vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::ctreshold [protected] |
double vslam::CovisibilityKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::minimum [protected] |