41 template<
class BaseOptimizerParameters>
58 : baseOptimizerParams(baseOptimizerParams) {
91 <<
"setMaxIterations: changing the max nr of iters might lead to less accurate solutions and is not recommended! " 93 maxIterations = maxIter;
103 relativeCostTol =
value;
123 for (
size_t i = 0;
i < knownIn.size();
i++){
124 knownInliers.push_back(knownIn[
i]);
126 std::sort(knownInliers.begin(), knownInliers.end());
134 for (
size_t i = 0;
i < knownOut.size();
i++){
135 knownOutliers.push_back(knownOut[
i]);
137 std::sort(knownOutliers.begin(), knownOutliers.end());
151 std::cout << str <<
"\n";
154 std::cout <<
"lossType: Geman McClure" <<
"\n";
157 std::cout <<
"lossType: Truncated Least-squares" <<
"\n";
160 throw std::runtime_error(
"GncParams::print: unknown loss type.");
162 std::cout <<
"maxIterations: " << maxIterations <<
"\n";
163 std::cout <<
"muStep: " << muStep <<
"\n";
164 std::cout <<
"relativeCostTol: " << relativeCostTol <<
"\n";
165 std::cout <<
"weightsTol: " << weightsTol <<
"\n";
166 std::cout <<
"verbosity: " << verbosity <<
"\n";
167 for (
size_t i = 0;
i < knownInliers.size();
i++)
168 std::cout <<
"knownInliers: " << knownInliers[
i] <<
"\n";
169 for (
size_t i = 0;
i < knownOutliers.size();
i++)
170 std::cout <<
"knownOutliers: " << knownOutliers[
i] <<
"\n";
171 baseOptimizerParams.print(
"Base optimizer params: ");
def step(data, isam, result, truth, currPoseIndex)
BaseOptimizerParameters::OptimizerType OptimizerType
For each parameter, specify the corresponding optimizer: e.g., GaussNewtonParams -> GaussNewtonOptimi...
void setWeightsTol(double value)
Set the maximum difference between the weights and their rounding in {0,1} to stop iterating...
bool equals(const GncParams &other, double tol=1e-9) const
Equals.
IndexVector knownOutliers
IndexVector knownInliers
Slots in the factor graph corresponding to measurements that we know are outliers.
Verbosity verbosity
Verbosity level.
GncLossType lossType
any other specific GNC parameters:
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
GncParams()
Default constructor.
double muStep
Multiplicative factor to reduce/increase the mu in gnc.
double relativeCostTol
If relative cost change is below this threshold, stop iterating.
BaseOptimizerParameters baseOptimizerParams
GNC parameters.
double weightsTol
If the weights are within weightsTol from being binary, stop iterating (only for TLS) ...
FastVector< uint64_t > IndexVector
Slots in the factor graph corresponding to measurements that we know are inliers. ...
GncParams(const BaseOptimizerParameters &baseOptimizerParams)
Constructor.
size_t maxIterations
Maximum number of iterations.
void setKnownInliers(const IndexVector &knownIn)
void setLossType(const GncLossType type)
Set the robust loss function to be used in GNC (chosen among the ones in GncLossType).
void setMuStep(const double step)
Set the graduated non-convexity step: at each GNC iteration, mu is updated as mu <- mu * muStep...
void setVerbosityGNC(const Verbosity value)
Set the verbosity level.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
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...
void setKnownOutliers(const IndexVector &knownOut)
GncLossType
Choice of robust loss function for GNC.
void setRelativeCostTol(double value)
Set the maximum relative difference in mu values to stop iterating.
void print(const std::string &str) const
Print.
Verbosity
Verbosity levels.