#include <GncParams.h>
Public Types | |
typedef BaseOptimizerParameters::OptimizerType | OptimizerType |
For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimizer. More... | |
enum | Verbosity { SILENT = 0, SUMMARY, VALUES } |
Verbosity levels. More... | |
Public Member Functions | |
bool | equals (const GncParams &other, double tol=1e-9) const |
Equals. More... | |
GncParams (const BaseOptimizerParameters &baseOptimizerParams) | |
Constructor. More... | |
GncParams () | |
Default constructor. More... | |
void | print (const std::string &str) const |
Print. More... | |
void | setKnownInliers (const std::vector< size_t > &knownIn) |
void | setLossType (const GncLossType type) |
Set the robust loss function to be used in GNC (chosen among the ones in GncLossType). More... | |
void | setMaxIterations (const size_t maxIter) |
Set the maximum number of iterations in GNC (changing the max nr of iters might lead to less accurate solutions and is not recommended). More... | |
void | setMuStep (const double step) |
Set the graduated non-convexity step: at each GNC iteration, mu is updated as mu <- mu * muStep. More... | |
void | setRelativeCostTol (double value) |
Set the maximum relative difference in mu values to stop iterating. More... | |
void | setVerbosityGNC (const Verbosity value) |
Set the verbosity level. More... | |
void | setWeightsTol (double value) |
Set the maximum difference between the weights and their rounding in {0,1} to stop iterating. More... | |
Public Attributes | |
BaseOptimizerParameters | baseOptimizerParams |
GNC parameters. More... | |
std::vector< size_t > | knownInliers = std::vector<size_t>() |
Slots in the factor graph corresponding to measurements that we know are inliers. More... | |
GncLossType | lossType = TLS |
any other specific GNC parameters: More... | |
size_t | maxIterations = 100 |
Maximum number of iterations. More... | |
double | muStep = 1.4 |
Multiplicative factor to reduce/increase the mu in gnc. More... | |
double | relativeCostTol = 1e-5 |
If relative cost change is below this threshold, stop iterating. More... | |
Verbosity | verbosity = SILENT |
Verbosity level. More... | |
double | weightsTol = 1e-4 |
If the weights are within weightsTol from being binary, stop iterating (only for TLS) More... | |
Definition at line 42 of file GncParams.h.
typedef BaseOptimizerParameters::OptimizerType gtsam::GncParams< BaseOptimizerParameters >::OptimizerType |
For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimizer.
Definition at line 45 of file GncParams.h.
enum gtsam::GncParams::Verbosity |
|
inline |
Constructor.
Definition at line 55 of file GncParams.h.
|
inline |
Default constructor.
Definition at line 60 of file GncParams.h.
|
inline |
Equals.
Definition at line 120 of file GncParams.h.
|
inline |
Print.
Definition at line 128 of file GncParams.h.
|
inline |
(Optional) Provide a vector of measurements that must be considered inliers. The enties in the vector corresponds to the slots in the factor graph. For instance, if you have a nonlinear factor graph nfg, and you provide knownIn = {0, 2, 15}, GNC will not apply outlier rejection to nfg[0], nfg[2], and nfg[15]. This functionality is commonly used in SLAM when one may assume the odometry is outlier free, and only apply GNC to prune outliers from the loop closures.
Definition at line 114 of file GncParams.h.
|
inline |
Set the robust loss function to be used in GNC (chosen among the ones in GncLossType).
Definition at line 76 of file GncParams.h.
|
inline |
Set the maximum number of iterations in GNC (changing the max nr of iters might lead to less accurate solutions and is not recommended).
Definition at line 81 of file GncParams.h.
|
inline |
Set the graduated non-convexity step: at each GNC iteration, mu is updated as mu <- mu * muStep.
Definition at line 89 of file GncParams.h.
|
inline |
Set the maximum relative difference in mu values to stop iterating.
Definition at line 94 of file GncParams.h.
|
inline |
Set the verbosity level.
Definition at line 104 of file GncParams.h.
|
inline |
Set the maximum difference between the weights and their rounding in {0,1} to stop iterating.
Definition at line 99 of file GncParams.h.
BaseOptimizerParameters gtsam::GncParams< BaseOptimizerParameters >::baseOptimizerParams |
GNC parameters.
Optimization parameters used to solve the weighted least squares problem at each GNC iteration
Definition at line 65 of file GncParams.h.
std::vector<size_t> gtsam::GncParams< BaseOptimizerParameters >::knownInliers = std::vector<size_t>() |
Slots in the factor graph corresponding to measurements that we know are inliers.
Definition at line 73 of file GncParams.h.
GncLossType gtsam::GncParams< BaseOptimizerParameters >::lossType = TLS |
size_t gtsam::GncParams< BaseOptimizerParameters >::maxIterations = 100 |
Maximum number of iterations.
Definition at line 68 of file GncParams.h.
double gtsam::GncParams< BaseOptimizerParameters >::muStep = 1.4 |
Multiplicative factor to reduce/increase the mu in gnc.
Definition at line 69 of file GncParams.h.
double gtsam::GncParams< BaseOptimizerParameters >::relativeCostTol = 1e-5 |
If relative cost change is below this threshold, stop iterating.
Definition at line 70 of file GncParams.h.
Verbosity gtsam::GncParams< BaseOptimizerParameters >::verbosity = SILENT |
Verbosity level.
Definition at line 72 of file GncParams.h.
double gtsam::GncParams< BaseOptimizerParameters >::weightsTol = 1e-4 |
If the weights are within weightsTol from being binary, stop iterating (only for TLS)
Definition at line 71 of file GncParams.h.