40 using namespace gtsam;
55 CHECK(lmParams.
equals(gncParams1b.baseOptimizerParams));
68 CHECK(gnParams.equals(gncParams2b.baseOptimizerParams));
73 CHECK(!gncParams2c.equals(gncParams2b.baseOptimizerParams));
90 CHECK(gnc.getFactors().equals(fg));
91 CHECK(gnc.getState().equals(initial));
92 CHECK(gnc.getParams().equals(gncParams));
98 CHECK(gnc.equals(gnc2));
118 CHECK(fg.equals(gnc.getFactors()));
207 CHECK(gnc.checkMuConvergence(mu));
217 CHECK(!gnc.checkMuConvergence(mu));
236 double prev_cost = 1.0;
239 CHECK(!gnc.checkCostConvergence(cost, prev_cost));
247 double prev_cost = 1.0;
250 CHECK(gnc.checkCostConvergence(cost, prev_cost));
269 Vector weights = Vector::Ones(fg.size());
270 CHECK(!gnc.checkWeightsConvergence(weights));
279 Vector weights = Vector::Ones(fg.size());
281 CHECK(gnc.checkWeightsConvergence(weights));
290 Vector weights = Vector::Ones(fg.size());
292 CHECK(!gnc.checkWeightsConvergence(weights));
302 Vector weights = Vector::Ones(fg.size());
304 CHECK(gnc.checkWeightsConvergence(weights));
323 CHECK(gnc.checkCostConvergence(1.0, 1.0));
324 CHECK(!gnc.checkCostConvergence(1.0, 2.0));
337 Vector weights_expected = Vector::Zero(4);
338 weights_expected[0] = 1.0;
339 weights_expected[1] = 1.0;
340 weights_expected[2] = 1.0;
341 weights_expected[3] =
std::pow(1.0 / (50.0 + 1.0), 2);
349 Vector weights_actual = gnc.calculateWeights(initial, mu);
354 weights_expected[3] =
std::pow(mu * barcSq / (50.0 + mu * barcSq), 2);
359 weights_actual = gnc2.calculateWeights(initial, mu);
372 Vector weights_expected = Vector::Zero(4);
373 weights_expected[0] = 1.0;
374 weights_expected[1] = 1.0;
375 weights_expected[2] = 1.0;
376 weights_expected[3] = 0;
383 Vector weights_actual = gnc.calculateWeights(initial, mu);
408 Vector weights_expected = Vector::Zero(1);
409 weights_expected[0] = 1.0;
419 Vector weights_actual = gnc.calculateWeights(initial, mu);
425 Vector weights_expected = Vector::Zero(1);
426 weights_expected[0] = 0.0;
435 Vector weights_actual = gnc.calculateWeights(initial, mu);
441 Vector weights_expected = Vector::Zero(1);
442 weights_expected[0] = 0.5;
451 Vector weights_actual = gnc.calculateWeights(initial, mu);
469 Vector weights = Vector::Ones(1);
500 Values actual = gnc.optimize();
534 Values gnc_result = gnc.optimize();
546 std::vector<size_t> knownInliers;
547 knownInliers.push_back(0);
548 knownInliers.push_back(1);
549 knownInliers.push_back(2);
560 Values gnc_result = gnc.optimize();
564 Vector finalWeights = gnc.getWeights();
577 Values gnc_result = gnc.optimize();
581 Vector finalWeights = gnc.getWeights();
597 Values gnc_result = gnc.optimize();
601 Vector finalWeights = gnc.getWeights();
623 std::vector<size_t> knownInliers;
624 knownInliers.push_back(0);
625 knownInliers.push_back(1);
626 knownInliers.push_back(2);
635 CHECK(
assert_equal(4.605170185988091 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1
e-3));
655 gnc.getInlierCostThresholds(), 1
e-3));
670 std::vector<size_t> knownInliers;
671 knownInliers.push_back(0);
672 knownInliers.push_back(1);
673 knownInliers.push_back(2);
682 Values gnc_result = gnc.optimize();
686 Vector finalWeights = gnc.getWeights();
690 CHECK(
assert_equal(2.0 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1
e-3));
700 Values gnc_result = gnc.optimize();
704 Vector finalWeights = gnc.getWeights();
708 CHECK(
assert_equal(2.0 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1
e-3));
718 boost::tie(graph, initial) =
load2D(filename);
723 graph->addPrior(0, priorMean, priorNoise);
746 Values actual = gnc.optimize();
void setWeightsTol(double value)
Set the maximum difference between the weights and their rounding in {0,1} to stop iterating...
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
static double Chi2inv(const double alpha, const size_t dofs)
void insert(Key j, const Value &val)
GraphAndValues load2D(const string &filename, SharedNoiseModel model, size_t maxIndex, bool addNoise, bool smart, NoiseFormat noiseFormat, KernelFunctionType kernelFunctionType)
#define DOUBLES_EQUAL(expected, actual, threshold)
NonlinearFactorGraph sharedRobustFactorGraphWithOutliers()
static const double sigma
NonlinearFactorGraph createReallyNonlinearFactorGraph()
NonlinearFactorGraph nonlinearFactorGraphWithGivenSigma(const double sigma)
static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5))
BaseOptimizerParameters baseOptimizerParams
GNC parameters.
static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5))
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
void setKnownInliers(const std::vector< size_t > &knownIn)
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
bool equals(const NonlinearOptimizerParams &other, double tol=1e-9) const
string findExampleDataFile(const string &name)
TEST(GncOptimizer, gncParamsConstructor)
boost::shared_ptr< This > shared_ptr
const ValueType at(Key j) const
void setLossType(const GncLossType type)
Set the robust loss function to be used in GNC (chosen among the ones in GncLossType).
void setVerbosity(const std::string &src)
void setMuStep(const double step)
Set the graduated non-convexity step: at each GNC iteration, mu is updated as mu <- mu * muStep...
Pose2 priorMean(0.0, 0.0, 0.0)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
noiseModel::Diagonal::shared_ptr SharedDiagonal
void setRelativeCostTol(double value)
Set the maximum relative difference in mu values to stop iterating.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
LevenbergMarquardtParams lmParams
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Create small example with two poses and one landmark.
noiseModel::Diagonal::shared_ptr priorNoise
double error(const Values &values) const
Jet< T, N > pow(const Jet< T, N > &f, double g)
NonlinearFactorGraph sharedNonRobustFactorGraphWithOutliers()
void setInlierCostThresholds(const double inth)
utility functions for loading datasets
noiseModel::Base::shared_ptr SharedNoiseModel