vslam Namespace Reference

Classes

class  PlaceRecognizer
 Recognizes previously seen frames. More...
class  voSt
 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...
class  VslamSystem
 VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA. More...
class  VslamSystemMono
 VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA on monocular images. More...

Typedefs

typedef std::vector
< frame_common::Frame,
Eigen::aligned_allocator
< frame_common::Frame > > 
FrameVector

Functions

void addPointCloudProjections (fc::Frame &f0, fc::Frame &f1, SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w_frame0, const Matrix< double, 3, 4 > &f2w_frame1, int ndi0, int ndi1, std::vector< int > *ipts)
void addPointCloudProjections (fc::Frame &f0, fc::Frame &f1, sba::SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w_frame0, const Matrix< double, 3, 4 > &f2w_frame1, int ndi0, int ndi1, std::vector< int > *ipts=NULL)
 Adds point-plane projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts.
void addProjections (fc::Frame &f0, fc::Frame &f1, std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &frames, SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w, int ndi0, int ndi1, std::vector< int > *ipts)
void addProjections (fc::Frame &f0, fc::Frame &f1, std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &frames, sba::SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w, int ndi0, int ndi1, std::vector< int > *ipts=NULL)
 Adds projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts.
Vector3d getProjection (fc::Frame &frame, int index)
 Get a Vector3d projection from a keypoint at index.
void substPointRef (std::vector< int > &ipts, int tri0, int tri1)
 substitutes tri0 for tri1 in a point reference vector.

Typedef Documentation

typedef std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> > vslam::FrameVector

Definition at line 43 of file place_recognizer.h.


Function Documentation

void vslam::addPointCloudProjections ( fc::Frame &  f0,
fc::Frame &  f1,
SysSBA &  sba,
const std::vector< cv::DMatch > &  inliers,
const Matrix< double, 3, 4 > &  f2w_frame0,
const Matrix< double, 3, 4 > &  f2w_frame1,
int  ndi0,
int  ndi1,
std::vector< int > *  ipts 
)

Definition at line 498 of file vo.cpp.

void vslam::addPointCloudProjections ( fc::Frame &  f0,
fc::Frame &  f1,
sba::SysSBA &  sba,
const std::vector< cv::DMatch > &  inliers,
const Matrix< double, 3, 4 > &  f2w_frame0,
const Matrix< double, 3, 4 > &  f2w_frame1,
int  ndi0,
int  ndi1,
std::vector< int > *  ipts = NULL 
)

Adds point-plane projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts.

Parameters:
f0 Previous frame.
f1 Newest frame to add.
sba SBA system to add the frames to.
inliers Matches between f0 and f1; indices of the points and projections to be added to the system.
f2w_frame0 Transform between the frame f0 to world coordinates.
f2w_frame1 Transform between the frame f1 to world coordinates.
ndi0 Node index of the old frame (f0) in SBA.
ndi1 Node index of the new frame (f1) in SBA.
ipts Optional parameter for a mapping between internal and external indices.
void vslam::addProjections ( fc::Frame &  f0,
fc::Frame &  f1,
std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &  frames,
SysSBA &  sba,
const std::vector< cv::DMatch > &  inliers,
const Matrix< double, 3, 4 > &  f2w,
int  ndi0,
int  ndi1,
std::vector< int > *  ipts 
)

Definition at line 405 of file vo.cpp.

void vslam::addProjections ( fc::Frame &  f0,
fc::Frame &  f1,
std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &  frames,
sba::SysSBA &  sba,
const std::vector< cv::DMatch > &  inliers,
const Matrix< double, 3, 4 > &  f2w,
int  ndi0,
int  ndi1,
std::vector< int > *  ipts = NULL 
)

Adds projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts.

Parameters:
f0 Previous frame.
f1 Newest frame to add.
frames All the frames in the system.
sba SBA system to add the frames to.
inliers Matches between f0 and f1; indices of the points and projections to be added to the system.
f2w Transform between the frame f0 to world coordinates.
ndi0 Node index of the old frame (f0) in SBA.
ndi1 Node index of the new frame (f1) in SBA.
ipts Optional parameter for a mapping between internal and external indices.
Vector3d vslam::getProjection ( fc::Frame &  frame,
int  index 
)

Get a Vector3d projection from a keypoint at index.

Definition at line 576 of file vo.cpp.

void vslam::substPointRef ( std::vector< int > &  ipts,
int  tri0,
int  tri1 
)

substitutes tri0 for tri1 in a point reference vector.

Definition at line 586 of file vo.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


vslam_system
Author(s): Kurt Konolige, Patrick Mihelich, Helen Oleynikova
autogenerated on Fri Jan 11 09:11:59 2013