#include <lc.h>
Public Member Functions | |
Params () | |
Parameter constructor. Sets the parameter struct to default values. | |
Public Attributes | |
string | desc_matching_type |
> Type of the descriptors (can be SIFT, SURF). | |
double | desc_thresh_ratio |
> Can be "CROSSCHECK" or "RATIO" | |
string | desc_type |
> Number of projections required. | |
int | epipolar_thresh |
> Descriptor threshold for crosscheck matching (typically between 0.7-0.9) or ratio for ratio matching (typically between 0.6-0.8). | |
int | group_range |
> Get the n first candidates of the hash matching (typically between 2-10). | |
string | image_dir |
> Directory where the library will save the image informations. | |
double | max_reproj_err |
> Minimum number of inliers to consider a matching as possible loop closure (>8). | |
int | min_inliers |
> Minimum number of descriptor matches to consider a matching as possible loop closure (>8). | |
int | min_matches |
> Maximum difference between images to be considered of the same group (typically between 5-10). | |
int | min_neighbor |
> Epipolar threshold. | |
int | n_candidates |
> Minimum number of neighbors that will be skipped for the loop closure (typically between 5-20, but depends on the frame rate). | |
int | num_proj |
> Directory where images will be saved (if save_images = True). | |
bool | save_images |
> Set to true to show logs in the screen. | |
bool | verbose |
> Maximum reprojection error (stereo only). | |
string | work_dir |
Static Public Attributes | |
static const double | DEFAULT_DESC_THRESH_RATIO = 0.8 |
static const int | DEFAULT_EPIPOLAR_THRESH = 1 |
static const int | DEFAULT_GROUP_RANGE = 5 |
static const double | DEFAULT_MAX_REPROJ_ERR = 2.0 |
static const int | DEFAULT_MIN_INLIERS = 12 |
static const int | DEFAULT_MIN_MATCHES = 20 |
static const int | DEFAULT_MIN_NEIGHBOR = 10 |
static const int | DEFAULT_N_CANDIDATES = 2 |
static const int | DEFAULT_NUM_PROJ = 2 |
> True to save the images into a directory. | |
static const bool | DEFAULT_SAVE_IMAGES = false |
static const bool | DEFAULT_VERBOSE = false |
const double haloc::LoopClosure::Params::DEFAULT_DESC_THRESH_RATIO = 0.8 [static] |
const int haloc::LoopClosure::Params::DEFAULT_EPIPOLAR_THRESH = 1 [static] |
const int haloc::LoopClosure::Params::DEFAULT_GROUP_RANGE = 5 [static] |
const double haloc::LoopClosure::Params::DEFAULT_MAX_REPROJ_ERR = 2.0 [static] |
const int haloc::LoopClosure::Params::DEFAULT_MIN_INLIERS = 12 [static] |
const int haloc::LoopClosure::Params::DEFAULT_MIN_MATCHES = 20 [static] |
const int haloc::LoopClosure::Params::DEFAULT_MIN_NEIGHBOR = 10 [static] |
const int haloc::LoopClosure::Params::DEFAULT_N_CANDIDATES = 2 [static] |
const int haloc::LoopClosure::Params::DEFAULT_NUM_PROJ = 2 [static] |
const bool haloc::LoopClosure::Params::DEFAULT_SAVE_IMAGES = false [static] |
const bool haloc::LoopClosure::Params::DEFAULT_VERBOSE = false [static] |