Public Member Functions | Public Attributes | Static Public Attributes
haloc::LoopClosure::Params Struct Reference

#include <lc.h>

List of all members.

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

Detailed Description

Definition at line 24 of file lc.h.


Constructor & Destructor Documentation

Parameter constructor. Sets the parameter struct to default values.

Definition at line 25 of file lc.cpp.


Member Data Documentation

Definition at line 48 of file lc.h.

Definition at line 49 of file lc.h.

Definition at line 52 of file lc.h.

Definition at line 55 of file lc.h.

Definition at line 54 of file lc.h.

Definition at line 53 of file lc.h.

Definition at line 50 of file lc.h.

Definition at line 51 of file lc.h.

> True to save the images into a directory.

Definition at line 47 of file lc.h.

Definition at line 57 of file lc.h.

const bool haloc::LoopClosure::Params::DEFAULT_VERBOSE = false [static]

Definition at line 56 of file lc.h.

> Type of the descriptors (can be SIFT, SURF).

Definition at line 34 of file lc.h.

> Can be "CROSSCHECK" or "RATIO"

Definition at line 35 of file lc.h.

> Number of projections required.

Definition at line 33 of file lc.h.

> Descriptor threshold for crosscheck matching (typically between 0.7-0.9) or ratio for ratio matching (typically between 0.6-0.8).

Definition at line 36 of file lc.h.

> Get the n first candidates of the hash matching (typically between 2-10).

Definition at line 39 of file lc.h.

> Directory where the library will save the image informations.

Definition at line 31 of file lc.h.

> Minimum number of inliers to consider a matching as possible loop closure (>8).

Definition at line 42 of file lc.h.

> Minimum number of descriptor matches to consider a matching as possible loop closure (>8).

Definition at line 41 of file lc.h.

> Maximum difference between images to be considered of the same group (typically between 5-10).

Definition at line 40 of file lc.h.

> Epipolar threshold.

Definition at line 37 of file lc.h.

> Minimum number of neighbors that will be skipped for the loop closure (typically between 5-20, but depends on the frame rate).

Definition at line 38 of file lc.h.

> Directory where images will be saved (if save_images = True).

Definition at line 32 of file lc.h.

> Set to true to show logs in the screen.

Definition at line 44 of file lc.h.

> Maximum reprojection error (stereo only).

Definition at line 43 of file lc.h.

Definition at line 30 of file lc.h.


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


libhaloc
Author(s): Pep Lluis Negre
autogenerated on Thu Jun 6 2019 21:25:00