svo
Semi-Direct Visual Odometry
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Static Public Member Functions | Private Member Functions | Private Attributes
svo::Config Class Reference

Global configuration file of SVO. More...

#include <config.h>

List of all members.

Static Public Member Functions

static ConfiggetInstance ()
static string & traceName ()
 Base-name of the tracefiles.
static string & traceDir ()
 Directory where the tracefiles are saved.
static size_t & nPyrLevels ()
 Number of pyramid levels used for features.
static bool & useImu ()
 Use the IMU to get relative rotations.
static size_t & coreNKfs ()
 Number of keyframes in the core. The core-kfs are optimized through bundle adjustment.
static double & mapScale ()
 Initial scale of the map. Depends on the distance the camera is moved for the initialization.
static size_t & gridSize ()
 Feature grid size of a cell in [px].
static double & initMinDisparity ()
 Initialization: Minimum required disparity between the first two frames.
static size_t & initMinTracked ()
 Initialization: Minimum number of tracked features.
static size_t & initMinInliers ()
 Initialization: Minimum number of inliers after RANSAC.
static size_t & kltMaxLevel ()
 Maximum level of the Lucas Kanade tracker.
static size_t & kltMinLevel ()
 Minimum level of the Lucas Kanade tracker.
static double & reprojThresh ()
 Reprojection threshold [px].
static double & poseOptimThresh ()
 Reprojection threshold after pose optimization.
static size_t & poseOptimNumIter ()
 Number of iterations in local bundle adjustment.
static size_t & structureOptimMaxPts ()
 Maximum number of points to optimize at every iteration.
static size_t & structureOptimNumIter ()
 Number of iterations in structure optimization.
static double & lobaThresh ()
 Reprojection threshold after bundle adjustment.
static double & lobaRobustHuberWidth ()
 Threshold for the robust Huber kernel of the local bundle adjustment.
static size_t & lobaNumIter ()
 Number of iterations in the local bundle adjustment.
static double & kfSelectMinDist ()
 Minimum distance between two keyframes. Relative to the average height in the map.
static double & triangMinCornerScore ()
 Select only features with a minimum Harris corner score for triangulation.
static size_t & subpixNIter ()
 Subpixel refinement of reprojection and triangulation. Set to 0 if no subpix refinement required!
static size_t & maxNKfs ()
 Limit the number of keyframes in the map.
static double & imgImuDelay ()
 How much (in milliseconds) is the camera delayed with respect to the imu.
static size_t & maxFts ()
 Maximum number of features that should be tracked.
static size_t & qualityMinFts ()
 If the number of tracked features drops below this threshold. Tracking quality is bad.
static int & qualityMaxFtsDrop ()
 If within one frame, this amount of features are dropped. Tracking quality is bad.

Private Member Functions

 Config ()
 Config (Config const &)
void operator= (Config const &)

Private Attributes

string trace_name
string trace_dir
size_t n_pyr_levels
bool use_imu
size_t core_n_kfs
double map_scale
size_t grid_size
double init_min_disparity
size_t init_min_tracked
size_t init_min_inliers
size_t klt_max_level
size_t klt_min_level
double reproj_thresh
double poseoptim_thresh
size_t poseoptim_num_iter
size_t structureoptim_max_pts
size_t structureoptim_num_iter
double loba_thresh
double loba_robust_huber_width
size_t loba_num_iter
double kfselect_mindist
double triang_min_corner_score
size_t triang_half_patch_size
size_t subpix_n_iter
size_t max_n_kfs
double img_imu_delay
size_t max_fts
size_t quality_min_fts
int quality_max_drop_fts

Detailed Description

Global configuration file of SVO.

Implements the Singleton design pattern to allow global access and to ensure that only one instance exists.


Constructor & Destructor Documentation

svo::Config::Config ( ) [private]
svo::Config::Config ( Config const &  ) [private]

Member Function Documentation

static size_t& svo::Config::coreNKfs ( ) [inline, static]

Number of keyframes in the core. The core-kfs are optimized through bundle adjustment.

static Config& svo::Config::getInstance ( ) [static]
static size_t& svo::Config::gridSize ( ) [inline, static]

Feature grid size of a cell in [px].

static double& svo::Config::imgImuDelay ( ) [inline, static]

How much (in milliseconds) is the camera delayed with respect to the imu.

static double& svo::Config::initMinDisparity ( ) [inline, static]

Initialization: Minimum required disparity between the first two frames.

static size_t& svo::Config::initMinInliers ( ) [inline, static]

Initialization: Minimum number of inliers after RANSAC.

static size_t& svo::Config::initMinTracked ( ) [inline, static]

Initialization: Minimum number of tracked features.

static double& svo::Config::kfSelectMinDist ( ) [inline, static]

Minimum distance between two keyframes. Relative to the average height in the map.

static size_t& svo::Config::kltMaxLevel ( ) [inline, static]

Maximum level of the Lucas Kanade tracker.

static size_t& svo::Config::kltMinLevel ( ) [inline, static]

Minimum level of the Lucas Kanade tracker.

static size_t& svo::Config::lobaNumIter ( ) [inline, static]

Number of iterations in the local bundle adjustment.

static double& svo::Config::lobaRobustHuberWidth ( ) [inline, static]

Threshold for the robust Huber kernel of the local bundle adjustment.

static double& svo::Config::lobaThresh ( ) [inline, static]

Reprojection threshold after bundle adjustment.

static double& svo::Config::mapScale ( ) [inline, static]

Initial scale of the map. Depends on the distance the camera is moved for the initialization.

static size_t& svo::Config::maxFts ( ) [inline, static]

Maximum number of features that should be tracked.

static size_t& svo::Config::maxNKfs ( ) [inline, static]

Limit the number of keyframes in the map.

This makes nslam essentially. a Visual Odometry. Set to 0 if unlimited number of keyframes are allowed. Minimum number of keyframes is 3.

static size_t& svo::Config::nPyrLevels ( ) [inline, static]

Number of pyramid levels used for features.

void svo::Config::operator= ( Config const &  ) [private]
static size_t& svo::Config::poseOptimNumIter ( ) [inline, static]

Number of iterations in local bundle adjustment.

static double& svo::Config::poseOptimThresh ( ) [inline, static]

Reprojection threshold after pose optimization.

static int& svo::Config::qualityMaxFtsDrop ( ) [inline, static]

If within one frame, this amount of features are dropped. Tracking quality is bad.

static size_t& svo::Config::qualityMinFts ( ) [inline, static]

If the number of tracked features drops below this threshold. Tracking quality is bad.

static double& svo::Config::reprojThresh ( ) [inline, static]

Reprojection threshold [px].

static size_t& svo::Config::structureOptimMaxPts ( ) [inline, static]

Maximum number of points to optimize at every iteration.

static size_t& svo::Config::structureOptimNumIter ( ) [inline, static]

Number of iterations in structure optimization.

static size_t& svo::Config::subpixNIter ( ) [inline, static]

Subpixel refinement of reprojection and triangulation. Set to 0 if no subpix refinement required!

static string& svo::Config::traceDir ( ) [inline, static]

Directory where the tracefiles are saved.

static string& svo::Config::traceName ( ) [inline, static]

Base-name of the tracefiles.

static double& svo::Config::triangMinCornerScore ( ) [inline, static]

Select only features with a minimum Harris corner score for triangulation.

static bool& svo::Config::useImu ( ) [inline, static]

Use the IMU to get relative rotations.


Member Data Documentation

size_t svo::Config::core_n_kfs [private]
size_t svo::Config::grid_size [private]
double svo::Config::img_imu_delay [private]
size_t svo::Config::klt_max_level [private]
size_t svo::Config::klt_min_level [private]
size_t svo::Config::loba_num_iter [private]
double svo::Config::loba_thresh [private]
double svo::Config::map_scale [private]
size_t svo::Config::max_fts [private]
size_t svo::Config::max_n_kfs [private]
size_t svo::Config::n_pyr_levels [private]
size_t svo::Config::quality_min_fts [private]
double svo::Config::reproj_thresh [private]
size_t svo::Config::subpix_n_iter [private]
string svo::Config::trace_dir [private]
string svo::Config::trace_name [private]
bool svo::Config::use_imu [private]

The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines