This is top-level calss for VO. More...
#include <vo.h>
Public Member Functions | |
virtual pair< pair< VertexD, VertexD >, bool > | getLastEdge () |
return last constructed edge in the pose-graph. | |
PoseGraphT & | getPoseGraph () |
shared_ptr< SE3 > | processPose (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, std::deque< SE3 > &past_poses, bool debug_images=false, bool trajectory_file=false) |
process new image. | |
shared_ptr< SE3 > | processPose (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, bool debug_images=false, bool trajectory_file=false) |
process new image. | |
virtual shared_ptr< VertexD > | processPose0 (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, bool debug_images=false, bool trajectory_file=false)=0 |
VisualOdometry (shared_ptr< NodeBuilderTT< PoseGraphT > > _nbuilder, shared_ptr< EdgeBuilder< PoseGraphT > > _ebuilder, size_t _target_past_verticies_size=2, shared_ptr< VodomLogger< PoseGraphT > > _logger=shared_ptr< VodomLogger< PoseGraphT > >()) | |
Protected Types | |
typedef graph_traits < PoseGraphT > ::vertex_descriptor | VertexD |
Protected Member Functions | |
void | pose2dVisualization (std::string prefix, typename graph_traits< PoseGraphT >::vertex_descriptor vd1, typename graph_traits< PoseGraphT >::vertex_descriptor vd2, typename NodeBuilderTT< PoseGraphT >::InputType input_vd1, typename NodeBuilderTT< PoseGraphT >::InputType input_vd2) |
draw debugging images for edge (vd1, vd2) | |
template<class T > | |
std::string | viewIDString (T view, T from, T to) |
Protected Attributes | |
shared_ptr< EdgeBuilder < PoseGraphT > > | ebuilder |
PoseGraphT | graph |
pose-graph class. | |
shared_ptr< VodomLogger < PoseGraphT > > | logger |
shared_ptr< NodeBuilderTT < PoseGraphT > > | nbuilder |
std::deque< VertexD > | past_vertices |
Points< PoseGraphT > | points |
landmark maneger class. | |
VertexD | pvd |
size_t | target_past_verticies_size |
VertexD | vd |
YAML::Emitter | yaml_out |
Static Protected Attributes | |
static const int | MINSEQ = 1000000 |
This is top-level calss for VO.
The VO is obtained by sucessive calls to VisualOdometry::processPose, which basically takes an image and produces T_wc, where w is world CF and c is camera cf for the given image.
NodeBuilderTT | Class template of the type fulfilling OneDetectorNodeBuilder interface |
PoseGraphT | boost::adjacency_list type. |
The implamentation of this interface also called _Keyframe Manager_.
typedef graph_traits<PoseGraphT>::vertex_descriptor vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::VertexD [protected] |
vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::VisualOdometry | ( | shared_ptr< NodeBuilderTT< PoseGraphT > > | _nbuilder, |
shared_ptr< EdgeBuilder< PoseGraphT > > | _ebuilder, | ||
size_t | _target_past_verticies_size = 2 , |
||
shared_ptr< VodomLogger< PoseGraphT > > | _logger = shared_ptr<VodomLogger<PoseGraphT> >() |
||
) | [inline] |
_nbuilder | instance of OneDetectorNodeBuilder to be used for processing new images. |
_ebuilder | instance of EdgeBuilder to be used for RBT estimate between nodes of the pose-graph. |
_target_past_verticies_size | number of past poses to store, see VisualOdometry::processPose |
virtual pair<pair<VertexD, VertexD>, bool> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::getLastEdge | ( | ) | [inline, virtual] |
PoseGraphT& vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::getPoseGraph | ( | ) | [inline] |
void vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::pose2dVisualization | ( | std::string | prefix, |
typename graph_traits< PoseGraphT >::vertex_descriptor | vd1, | ||
typename graph_traits< PoseGraphT >::vertex_descriptor | vd2, | ||
typename NodeBuilderTT< PoseGraphT >::InputType | input_vd1, | ||
typename NodeBuilderTT< PoseGraphT >::InputType | input_vd2 | ||
) | [inline, protected] |
shared_ptr<SE3> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose | ( | typename NodeBuilderTT< PoseGraphT >::InputType | input, |
int | pose_id, | ||
uint64_t | pose_timestamp, | ||
std::deque< SE3 > & | past_poses, | ||
bool | debug_images = false , |
||
bool | trajectory_file = false |
||
) | [inline] |
process new image.
input | input data required by NodeBuilderTT to produce new pose-graph pose. This is typically an image, but may be something else in simulation. |
pose_id | image ID that is used in the debugging output associate poses to images. |
past_poses | RBTs for VisualOdometry::target_past_verticies_size most recent poses. |
shared_ptr<SE3> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose | ( | typename NodeBuilderTT< PoseGraphT >::InputType | input, |
int | pose_id, | ||
uint64_t | pose_timestamp, | ||
bool | debug_images = false , |
||
bool | trajectory_file = false |
||
) | [inline] |
virtual shared_ptr<VertexD> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose0 | ( | typename NodeBuilderTT< PoseGraphT >::InputType | input, |
int | pose_id, | ||
uint64_t | pose_timestamp, | ||
bool | debug_images = false , |
||
bool | trajectory_file = false |
||
) | [pure virtual] |
Implemented in vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.
std::string vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::viewIDString | ( | T | view, |
T | from, | ||
T | to | ||
) | [inline, protected] |
shared_ptr<EdgeBuilder<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::ebuilder [protected] |
PoseGraphT vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::graph [protected] |
shared_ptr<VodomLogger<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::logger [protected] |
const int vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::MINSEQ = 1000000 [static, protected] |
shared_ptr<NodeBuilderTT<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::nbuilder [protected] |
std::deque<VertexD> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::past_vertices [protected] |
Stores VisualOdometry::target_past_verticies_size most recent vertices
Points<PoseGraphT> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::points [protected] |
VertexD vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::pvd [protected] |
size_t vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::target_past_verticies_size [protected] |
VertexD vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::vd [protected] |
YAML::Emitter vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::yaml_out [protected] |