vslam::VslamSystem Class Reference

VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA. More...

#include <vslam.h>

Inheritance diagram for vslam::VslamSystem:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool addFrame (const frame_common::CamParams &camera_parameters, const cv::Mat &left, const cv::Mat &right, const pcl::PointCloud< pcl::PointXYZRGB > &ptcloud, int nfrac=0)
 Add a frame to the system.
bool addFrame (const frame_common::CamParams &camera_parameters, const cv::Mat &left, const cv::Mat &right, int nfrac=0, bool setPointCloud=false)
 Add a frame to the system.
void addKeyframe (frame_common::Frame &next_frame)
void refine (int initial_runs=3)
 Perform a refinement on the large-scale SBA system.
void setHuber (double x)
 Set the window size for place recognition matching.
void setKeyAngle (double n)
 Set minimum keyframe distance in meters.
void setKeyDist (double n)
 Set keyframe inliers.
void setKeyInliers (int n)
 Set number of keyframes to skip for Place Recognition.
void setNDisp (int n)
 Set minimum keyframe angle in radians.
void setPlaceInliers (int n)
void setPointcloudProc (boost::shared_ptr< frame_common::PointcloudProc > proc)
 Set the pointcloud processor.
void setPRPolish (bool n)
 Set the number of RANSAC iterations for place recognition pose estimate.
void setPRRansacIt (int n)
 Set the number of disparities in stereo processing.
void setPRSkip (int n)
 Place recognition inliers.
void setPRWindow (int x, int y)
 Set whether to polish pose estimate for visual odometry using SBA.
void setVOPolish (bool n)
 Set the number of RANSAC iterations for visual odometry pose estimate.
void setVORansacIt (int n)
 Set whether to polish the place recognition pose estimate using SBA.
void setVOWindow (int x, int y)
 Set the window size for place recognition matching.
 VslamSystem (const std::string &vocab_tree_file, const std::string &vocab_weights_file, int min_keyframe_inliers=0, double min_keyframe_distance=0.2, double min_keyframe_angle=0.1)
 Constructor for VslamSystem.

Public Attributes

bool doPointPlane
frame_common::FrameProc frame_processor_
std::vector
< frame_common::Frame,
Eigen::aligned_allocator
< frame_common::Frame > > 
frames_
 Image frames in system.
int nSkip
 Number of the most recent frames to skip for PR checking.
int numPRs
 Number of place recognitions that succeeded.
vslam::PlaceRecognizer place_recognizer_
 Place recognizer.
std::vector< cv::DMatch > pointcloud_matches_
 Pointcloud matches.
boost::shared_ptr
< frame_common::PointcloudProc > 
pointcloud_processor_
 Pointer to pointcloud processor.
pe::PoseEstimator3d pose_estimator_
 For place recognition matches.
int prInliers
 Number of inliers needed for PR match.
sba::SysSBA sba_
 Large-scale SBA system.
vslam::voSt vo_
 Visual odometry processor.

Detailed Description

VSLAM class that performs visual odometry, loop closure through place recognition, and large-scale optimization using SBA.

Definition at line 12 of file vslam.h.


Constructor & Destructor Documentation

vslam::VslamSystem::VslamSystem ( const std::string &  vocab_tree_file,
const std::string &  vocab_weights_file,
int  min_keyframe_inliers = 0,
double  min_keyframe_distance = 0.2,
double  min_keyframe_angle = 0.1 
)

Constructor for VslamSystem.

Parameters:
vocab_tree_file Path to the vocabulary tree file.
vocab_weights_file Path to the vocabulary tree weights file.
min_keyframe_distance Minimum distance between keyframes, in meters.
min_keyframe_angle Minimum angle between keyframes, in radians.
min_keyframe_inliers Minimum inliers in keyframes.

Todo:
Don't use windowed matching for place rec

Definition at line 44 of file vslam.cpp.


Member Function Documentation

bool vslam::VslamSystem::addFrame ( const frame_common::CamParams &  camera_parameters,
const cv::Mat &  left,
const cv::Mat &  right,
const pcl::PointCloud< pcl::PointXYZRGB > &  ptcloud,
int  nfrac = 0 
)

Add a frame to the system.

Parameters:
camera_parameters Camera parameters for the cameras.
left Left image.
right Right image.
ptcloud Pointcloud to add to the frame.
nfrac Fractional disparity. If above 0, then right is an int16_t disparity image.
bool vslam::VslamSystem::addFrame ( const frame_common::CamParams &  camera_parameters,
const cv::Mat &  left,
const cv::Mat &  right,
int  nfrac = 0,
bool  setPointCloud = false 
)

Add a frame to the system.

Parameters:
camera_parameters Camera parameters for the cameras.
left Left image.
right Right image.
nfrac Fractional disparity. If above 0, then right is an int16_t disparity image.
setPointCloud. True if point cloud is to be set up from disparities

Definition at line 69 of file vslam.cpp.

void vslam::VslamSystem::addKeyframe ( frame_common::Frame &  next_frame  ) 

Todo:
What does 'fq0' mean?

Definition at line 141 of file vslam.cpp.

void vslam::VslamSystem::refine ( int  initial_runs = 3  ) 

Perform a refinement on the large-scale SBA system.

Parameters:
initial_runs How many iterations to do SBA for.

Todo:
Make these arguments parameters?

Definition at line 218 of file vslam.cpp.

void vslam::VslamSystem::setHuber ( double  x  )  [inline]

Set the window size for place recognition matching.

Definition at line 80 of file vslam.h.

void vslam::VslamSystem::setKeyAngle ( double  n  )  [inline]

Set minimum keyframe distance in meters.

Definition at line 72 of file vslam.h.

void vslam::VslamSystem::setKeyDist ( double  n  )  [inline]

Set keyframe inliers.

Definition at line 71 of file vslam.h.

void vslam::VslamSystem::setKeyInliers ( int  n  )  [inline]

Set number of keyframes to skip for Place Recognition.

Definition at line 70 of file vslam.h.

void vslam::VslamSystem::setNDisp ( int  n  )  [inline]

Set minimum keyframe angle in radians.

Definition at line 73 of file vslam.h.

void vslam::VslamSystem::setPlaceInliers ( int  n  )  [inline]

Definition at line 68 of file vslam.h.

void vslam::VslamSystem::setPointcloudProc ( boost::shared_ptr< frame_common::PointcloudProc >  proc  )  [inline]

Set the pointcloud processor.

Definition at line 85 of file vslam.h.

void vslam::VslamSystem::setPRPolish ( bool  n  )  [inline]

Set the number of RANSAC iterations for place recognition pose estimate.

Definition at line 75 of file vslam.h.

void vslam::VslamSystem::setPRRansacIt ( int  n  )  [inline]

Set the number of disparities in stereo processing.

Definition at line 74 of file vslam.h.

void vslam::VslamSystem::setPRSkip ( int  n  )  [inline]

Place recognition inliers.

Definition at line 69 of file vslam.h.

void vslam::VslamSystem::setPRWindow ( int  x,
int  y 
) [inline]

Set whether to polish pose estimate for visual odometry using SBA.

Definition at line 78 of file vslam.h.

void vslam::VslamSystem::setVOPolish ( bool  n  )  [inline]

Set the number of RANSAC iterations for visual odometry pose estimate.

Definition at line 77 of file vslam.h.

void vslam::VslamSystem::setVORansacIt ( int  n  )  [inline]

Set whether to polish the place recognition pose estimate using SBA.

Definition at line 76 of file vslam.h.

void vslam::VslamSystem::setVOWindow ( int  x,
int  y 
) [inline]

Set the window size for place recognition matching.

Definition at line 79 of file vslam.h.


Member Data Documentation

Definition at line 22 of file vslam.h.

frame_common::FrameProc vslam::VslamSystem::frame_processor_
Todo:
Leave these protected

Frame processor for new frames.

Definition at line 10 of file vslam.h.

std::vector<frame_common::Frame, Eigen::aligned_allocator<frame_common::Frame> > vslam::VslamSystem::frames_

Image frames in system.

Definition at line 12 of file vslam.h.

Number of the most recent frames to skip for PR checking.

Definition at line 65 of file vslam.h.

Number of place recognitions that succeeded.

Definition at line 64 of file vslam.h.

Place recognizer.

Definition at line 15 of file vslam.h.

std::vector<cv::DMatch> vslam::VslamSystem::pointcloud_matches_

Pointcloud matches.

Definition at line 21 of file vslam.h.

boost::shared_ptr<frame_common::PointcloudProc> vslam::VslamSystem::pointcloud_processor_

Pointer to pointcloud processor.

Definition at line 19 of file vslam.h.

For place recognition matches.

Definition at line 16 of file vslam.h.

Number of inliers needed for PR match.

Definition at line 63 of file vslam.h.

Large-scale SBA system.

Definition at line 13 of file vslam.h.

Visual odometry processor.

Definition at line 14 of file vslam.h.


The documentation for this class was generated from the following files:
 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