Public Member Functions | Public Attributes | Private Attributes
vslam::voSt Class Reference

Stereo visual odometry class. Keeps track of a certain size window of latest frames in the system, estimates pose changes between frames, and optimizes the window using SBA. More...

#include <vo.h>

List of all members.

Public Member Functions

bool addFrame (const fc::Frame &fnew)
 Add a new frame to the system, if it is a keyframe.
int findNode (int frameId)
 Finds sba node index of associated frame.
int findTransform (int frameId, int n, Vector4d &trans, Quaterniond &qrot, Matrix< double, 6, 6 > &prec)
 Gets the transform between frames.
void removeFrame ()
 Removes oldest frame from the system.
void transferLatestFrame (std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &eframes, sba::SysSBA &esba)
 Transfers frames to external sba system.
 voSt (boost::shared_ptr< pe::PoseEstimator > pose_estimator, int ws=20, int wf=5, int mininls=800, double mind=0.1, double mina=0.1)
 Constructor for voSt class.

Public Attributes

bool doPointPlane
std::vector< fc::Frame,
Eigen::aligned_allocator
< fc::Frame > > 
frames
 Previous frames in the system.
vector< int > ipts
 External point index, for relating internal sba points to external points.
double minang
 Minimum angular distance between keyframes (radians).
double mindist
 Minimum linear distance between keyframes (meters).
int mininls
 Minimum number of inliers.
boost::shared_ptr
< frame_common::PointcloudProc
pointcloud_proc_
 Pointer to pointcloud processor.
boost::shared_ptr
< pe::PoseEstimator
pose_estimator_
 Pointer to pose estimator object.
sba::SysSBA sba
 VO's internal SBA system, which holds the VO window.
int wfixed
 Number of fixed frames at the beginning of the window.
int wsize
 Size of window in frames.

Private Attributes

std::vector< cv::DMatch > pointcloud_matches_
 Pointcloud matches.

Detailed Description

Stereo visual odometry class. Keeps track of a certain size window of latest frames in the system, estimates pose changes between frames, and optimizes the window using SBA.

Definition at line 60 of file vo.h.


Constructor & Destructor Documentation

vslam::voSt::voSt ( boost::shared_ptr< pe::PoseEstimator pose_estimator,
int  ws = 20,
int  wf = 5,
int  mininls = 800,
double  mind = 0.1,
double  mina = 0.1 
)

Constructor for voSt class.

Parameters:
pose_estimatorpointer to PoseEstimator object to use for matching frames.
wsWindow size for VO's internal SBA system; that is, how many frames to keep track of at a time.
wfWindow fixed size; how many of the first frames in the system to keep fixed.
mininlsMinimum number of point inliers to keep a frame.
mindMinimum linear distance between keyframes (meters).
minaMinimum angular distance between keyframes (radians).

Definition at line 52 of file vo.cpp.


Member Function Documentation

bool vslam::voSt::addFrame ( const fc::Frame fnew)

Add a new frame to the system, if it is a keyframe.

Parameters:
fnewThe frame to be added.
Returns:
Whether the frame was added as a keyframe.

Definition at line 73 of file vo.cpp.

int vslam::voSt::findNode ( int  frameId)

Finds sba node index of associated frame.

Definition at line 393 of file vo.cpp.

int vslam::voSt::findTransform ( int  frameId,
int  n,
Vector4d &  trans,
Quaterniond &  qrot,
Matrix< double, 6, 6 > &  prec 
)

Gets the transform between frames.

Parameters:
frameIdID of the first frame.
nNumber of frames ahead the second frame is (frameId + n).
transTranslation between the two frames (meters).
qrotRotation between the two frames.
Returns:
Frame ID of the second frame.

Definition at line 362 of file vo.cpp.

Removes oldest frame from the system.

Definition at line 205 of file vo.cpp.

void vslam::voSt::transferLatestFrame ( std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &  eframes,
sba::SysSBA esba 
)

Transfers frames to external sba system.

Parameters:
eframesA vector of external frames. The last frame in this will be transferred.
esbaExternal SBA system to add the frame to.

NOTE! set for NewCollege data

should use relative pose between last two VO frames

TODO this also assume most recent VO operation was a keyframe should reconstruct inliers from most recent two frames

Definition at line 278 of file vo.cpp.


Member Data Documentation

Definition at line 119 of file vo.h.

std::vector<fc::Frame, Eigen::aligned_allocator<fc::Frame> > vslam::voSt::frames

Previous frames in the system.

Definition at line 112 of file vo.h.

vector<int> vslam::voSt::ipts

External point index, for relating internal sba points to external points.

Definition at line 76 of file vo.h.

Minimum angular distance between keyframes (radians).

Definition at line 83 of file vo.h.

Minimum linear distance between keyframes (meters).

Definition at line 82 of file vo.h.

Minimum number of inliers.

Definition at line 84 of file vo.h.

std::vector<cv::DMatch> vslam::voSt::pointcloud_matches_ [private]

Pointcloud matches.

Definition at line 125 of file vo.h.

Pointer to pointcloud processor.

Definition at line 118 of file vo.h.

Pointer to pose estimator object.

Definition at line 115 of file vo.h.

VO's internal SBA system, which holds the VO window.

Definition at line 73 of file vo.h.

Number of fixed frames at the beginning of the window.

Definition at line 79 of file vo.h.

Size of window in frames.

Definition at line 78 of file vo.h.


The documentation for this class was generated from the following files:


vslam_system
Author(s): Kurt Konolige, Patrick Mihelich, Helen Oleynikova
autogenerated on Thu Jan 2 2014 12:12:32