testGncOptimizer.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file testGncOptimizer.cpp
  10. * @brief Unit tests for GncOptimizer class
  11. * @author Jingnan Shi
  12. * @author Luca Carlone
  13. * @author Frank Dellaert
  14. *
  15. * Implementation of the paper: Yang, Antonante, Tzoumas, Carlone, "Graduated
  16. * Non-Convexity for Robust Spatial Perception: From Non-Minimal Solvers to
  17. * Global Outlier Rejection", ICRA/RAL, 2020. (arxiv version:
  18. * https://arxiv.org/pdf/1909.08605.pdf)
  19. *
  20. * See also:
  21. * Antonante, Tzoumas, Yang, Carlone, "Outlier-Robust Estimation: Hardness,
  22. * Minimally-Tuned Algorithms, and Applications", arxiv:
  23. * https://arxiv.org/pdf/2007.15109.pdf, 2020.
  24. */
  25. #include <CppUnitLite/TestHarness.h>
  26. #include <gtsam/nonlinear/GncOptimizer.h>
  27. #include <gtsam/nonlinear/LinearContainerFactor.h>
  28. #include <gtsam/slam/dataset.h>
  29. #include <tests/smallExample.h>
  30. #include <gtsam/sam/BearingFactor.h>
  31. #include <gtsam/geometry/Pose2.h>
  32. using namespace std;
  33. using namespace gtsam;
  34. using symbol_shorthand::L;
  35. using symbol_shorthand::X;
  36. static double tol = 1e-7;
  37. /* ************************************************************************* */
  38. TEST(GncOptimizer, gncParamsConstructor) {
  39. // check params are correctly parsed
  40. LevenbergMarquardtParams lmParams;
  41. GncParams<LevenbergMarquardtParams> gncParams1(lmParams);
  42. CHECK(lmParams.equals(gncParams1.baseOptimizerParams));
  43. // check also default constructor
  44. GncParams<LevenbergMarquardtParams> gncParams1b;
  45. CHECK(lmParams.equals(gncParams1b.baseOptimizerParams));
  46. // and check params become different if we change lmParams
  47. lmParams.setVerbosity("DELTA");
  48. CHECK(!lmParams.equals(gncParams1.baseOptimizerParams));
  49. // and same for GN
  50. GaussNewtonParams gnParams;
  51. GncParams<GaussNewtonParams> gncParams2(gnParams);
  52. CHECK(gnParams.equals(gncParams2.baseOptimizerParams));
  53. // check default constructor
  54. GncParams<GaussNewtonParams> gncParams2b;
  55. CHECK(gnParams.equals(gncParams2b.baseOptimizerParams));
  56. // change something at the gncParams level
  57. GncParams<GaussNewtonParams> gncParams2c(gncParams2b);
  58. gncParams2c.setLossType(GncLossType::GM);
  59. CHECK(!gncParams2c.equals(gncParams2b.baseOptimizerParams));
  60. }
  61. /* ************************************************************************* */
  62. TEST(GncOptimizer, gncConstructor) {
  63. // has to have Gaussian noise models !
  64. auto fg = example::createReallyNonlinearFactorGraph(); // just a unary factor
  65. // on a 2D point
  66. Point2 p0(3, 3);
  67. Values initial;
  68. initial.insert(X(1), p0);
  69. GncParams<LevenbergMarquardtParams> gncParams;
  70. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  71. gncParams);
  72. CHECK(gnc.getFactors().equals(fg));
  73. CHECK(gnc.getState().equals(initial));
  74. CHECK(gnc.getParams().equals(gncParams));
  75. auto gnc2 = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  76. gncParams);
  77. // check the equal works
  78. CHECK(gnc.equals(gnc2));
  79. }
  80. /* ************************************************************************* */
  81. TEST(GncOptimizer, gncConstructorWithRobustGraphAsInput) {
  82. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  83. // same graph with robust noise model
  84. auto fg_robust = example::sharedRobustFactorGraphWithOutliers();
  85. Point2 p0(3, 3);
  86. Values initial;
  87. initial.insert(X(1), p0);
  88. GncParams<LevenbergMarquardtParams> gncParams;
  89. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg_robust,
  90. initial,
  91. gncParams);
  92. // make sure that when parsing the graph is transformed into one without
  93. // robust loss
  94. CHECK(fg.equals(gnc.getFactors()));
  95. }
  96. /* ************************************************************************* */
  97. TEST(GncOptimizer, initializeMu) {
  98. auto fg = example::createReallyNonlinearFactorGraph();
  99. Point2 p0(3, 3);
  100. Values initial;
  101. initial.insert(X(1), p0);
  102. // testing GM mu initialization
  103. GncParams<LevenbergMarquardtParams> gncParams;
  104. gncParams.setLossType(GncLossType::GM);
  105. auto gnc_gm = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  106. gncParams);
  107. gnc_gm.setInlierCostThresholds(1.0);
  108. // according to rmk 5 in the gnc paper: m0 = 2 rmax^2 / barcSq
  109. // (barcSq=1 in this example)
  110. EXPECT_DOUBLES_EQUAL(gnc_gm.initializeMu(), 2 * 198.999, 1e-3);
  111. // testing TLS mu initialization
  112. gncParams.setLossType(GncLossType::TLS);
  113. auto gnc_tls = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  114. gncParams);
  115. gnc_tls.setInlierCostThresholds(1.0);
  116. // according to rmk 5 in the gnc paper: m0 = barcSq / (2 * rmax^2 - barcSq)
  117. // (barcSq=1 in this example)
  118. EXPECT_DOUBLES_EQUAL(gnc_tls.initializeMu(), 1 / (2 * 198.999 - 1), 1e-3);
  119. }
  120. /* ************************************************************************* */
  121. TEST(GncOptimizer, updateMuGM) {
  122. // has to have Gaussian noise models !
  123. auto fg = example::createReallyNonlinearFactorGraph();
  124. Point2 p0(3, 3);
  125. Values initial;
  126. initial.insert(X(1), p0);
  127. GncParams<LevenbergMarquardtParams> gncParams;
  128. gncParams.setLossType(GncLossType::GM);
  129. gncParams.setMuStep(1.4);
  130. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  131. gncParams);
  132. double mu = 5.0;
  133. EXPECT_DOUBLES_EQUAL(gnc.updateMu(mu), mu / 1.4, tol);
  134. // check it correctly saturates to 1 for GM
  135. mu = 1.2;
  136. EXPECT_DOUBLES_EQUAL(gnc.updateMu(mu), 1.0, tol);
  137. }
  138. /* ************************************************************************* */
  139. TEST(GncOptimizer, updateMuTLS) {
  140. // has to have Gaussian noise models !
  141. auto fg = example::createReallyNonlinearFactorGraph();
  142. Point2 p0(3, 3);
  143. Values initial;
  144. initial.insert(X(1), p0);
  145. GncParams<LevenbergMarquardtParams> gncParams;
  146. gncParams.setMuStep(1.4);
  147. gncParams.setLossType(GncLossType::TLS);
  148. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  149. gncParams);
  150. double mu = 5.0;
  151. EXPECT_DOUBLES_EQUAL(gnc.updateMu(mu), mu * 1.4, tol);
  152. }
  153. /* ************************************************************************* */
  154. TEST(GncOptimizer, checkMuConvergence) {
  155. // has to have Gaussian noise models !
  156. auto fg = example::createReallyNonlinearFactorGraph();
  157. Point2 p0(3, 3);
  158. Values initial;
  159. initial.insert(X(1), p0);
  160. {
  161. GncParams<LevenbergMarquardtParams> gncParams;
  162. gncParams.setLossType(GncLossType::GM);
  163. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  164. gncParams);
  165. double mu = 1.0;
  166. CHECK(gnc.checkMuConvergence(mu));
  167. }
  168. {
  169. GncParams<LevenbergMarquardtParams> gncParams;
  170. gncParams.setLossType(
  171. GncLossType::TLS);
  172. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  173. gncParams);
  174. double mu = 1.0;
  175. CHECK(!gnc.checkMuConvergence(mu)); //always false for TLS
  176. }
  177. }
  178. /* ************************************************************************* */
  179. TEST(GncOptimizer, checkCostConvergence) {
  180. // has to have Gaussian noise models !
  181. auto fg = example::createReallyNonlinearFactorGraph();
  182. Point2 p0(3, 3);
  183. Values initial;
  184. initial.insert(X(1), p0);
  185. {
  186. GncParams<LevenbergMarquardtParams> gncParams;
  187. gncParams.setRelativeCostTol(0.49);
  188. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  189. gncParams);
  190. double prev_cost = 1.0;
  191. double cost = 0.5;
  192. // relative cost reduction = 0.5 > 0.49, hence checkCostConvergence = false
  193. CHECK(!gnc.checkCostConvergence(cost, prev_cost));
  194. }
  195. {
  196. GncParams<LevenbergMarquardtParams> gncParams;
  197. gncParams.setRelativeCostTol(0.51);
  198. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  199. gncParams);
  200. double prev_cost = 1.0;
  201. double cost = 0.5;
  202. // relative cost reduction = 0.5 < 0.51, hence checkCostConvergence = true
  203. CHECK(gnc.checkCostConvergence(cost, prev_cost));
  204. }
  205. }
  206. /* ************************************************************************* */
  207. TEST(GncOptimizer, checkWeightsConvergence) {
  208. // has to have Gaussian noise models !
  209. auto fg = example::createReallyNonlinearFactorGraph();
  210. Point2 p0(3, 3);
  211. Values initial;
  212. initial.insert(X(1), p0);
  213. {
  214. GncParams<LevenbergMarquardtParams> gncParams;
  215. gncParams.setLossType(GncLossType::GM);
  216. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  217. gncParams);
  218. Vector weights = Vector::Ones(fg.size());
  219. CHECK(!gnc.checkWeightsConvergence(weights)); //always false for GM
  220. }
  221. {
  222. GncParams<LevenbergMarquardtParams> gncParams;
  223. gncParams.setLossType(
  224. GncLossType::TLS);
  225. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  226. gncParams);
  227. Vector weights = Vector::Ones(fg.size());
  228. // weights are binary, so checkWeightsConvergence = true
  229. CHECK(gnc.checkWeightsConvergence(weights));
  230. }
  231. {
  232. GncParams<LevenbergMarquardtParams> gncParams;
  233. gncParams.setLossType(
  234. GncLossType::TLS);
  235. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  236. gncParams);
  237. Vector weights = Vector::Ones(fg.size());
  238. weights[0] = 0.9; // more than weightsTol = 1e-4 from 1, hence checkWeightsConvergence = false
  239. CHECK(!gnc.checkWeightsConvergence(weights));
  240. }
  241. {
  242. GncParams<LevenbergMarquardtParams> gncParams;
  243. gncParams.setLossType(
  244. GncLossType::TLS);
  245. gncParams.setWeightsTol(0.1);
  246. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  247. gncParams);
  248. Vector weights = Vector::Ones(fg.size());
  249. weights[0] = 0.9; // exactly weightsTol = 0.1 from 1, hence checkWeightsConvergence = true
  250. CHECK(gnc.checkWeightsConvergence(weights));
  251. }
  252. }
  253. /* ************************************************************************* */
  254. TEST(GncOptimizer, checkConvergenceTLS) {
  255. // has to have Gaussian noise models !
  256. auto fg = example::createReallyNonlinearFactorGraph();
  257. Point2 p0(3, 3);
  258. Values initial;
  259. initial.insert(X(1), p0);
  260. GncParams<LevenbergMarquardtParams> gncParams;
  261. gncParams.setRelativeCostTol(1e-5);
  262. gncParams.setLossType(GncLossType::TLS);
  263. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  264. gncParams);
  265. CHECK(gnc.checkCostConvergence(1.0, 1.0));
  266. CHECK(!gnc.checkCostConvergence(1.0, 2.0));
  267. }
  268. /* ************************************************************************* */
  269. TEST(GncOptimizer, calculateWeightsGM) {
  270. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  271. Point2 p0(0, 0);
  272. Values initial;
  273. initial.insert(X(1), p0);
  274. // we have 4 factors, 3 with zero errors (inliers), 1 with error 50 = 0.5 *
  275. // 1/sigma^2 || [1;0] - [0;0] ||^2 (outlier)
  276. Vector weights_expected = Vector::Zero(4);
  277. weights_expected[0] = 1.0; // zero error
  278. weights_expected[1] = 1.0; // zero error
  279. weights_expected[2] = 1.0; // zero error
  280. weights_expected[3] = std::pow(1.0 / (50.0 + 1.0), 2); // outlier, error = 50
  281. GaussNewtonParams gnParams;
  282. GncParams<GaussNewtonParams> gncParams(gnParams);
  283. gncParams.setLossType(GncLossType::GM);
  284. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial, gncParams);
  285. gnc.setInlierCostThresholds(1.0);
  286. double mu = 1.0;
  287. Vector weights_actual = gnc.calculateWeights(initial, mu);
  288. CHECK(assert_equal(weights_expected, weights_actual, tol));
  289. mu = 2.0;
  290. double barcSq = 5.0;
  291. weights_expected[3] = std::pow(mu * barcSq / (50.0 + mu * barcSq), 2); // outlier, error = 50
  292. auto gnc2 = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  293. gncParams);
  294. gnc2.setInlierCostThresholds(barcSq);
  295. weights_actual = gnc2.calculateWeights(initial, mu);
  296. CHECK(assert_equal(weights_expected, weights_actual, tol));
  297. }
  298. /* ************************************************************************* */
  299. TEST(GncOptimizer, calculateWeightsTLS) {
  300. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  301. Point2 p0(0, 0);
  302. Values initial;
  303. initial.insert(X(1), p0);
  304. // we have 4 factors, 3 with zero errors (inliers), 1 with error
  305. Vector weights_expected = Vector::Zero(4);
  306. weights_expected[0] = 1.0; // zero error
  307. weights_expected[1] = 1.0; // zero error
  308. weights_expected[2] = 1.0; // zero error
  309. weights_expected[3] = 0; // outliers
  310. GaussNewtonParams gnParams;
  311. GncParams<GaussNewtonParams> gncParams(gnParams);
  312. gncParams.setLossType(GncLossType::TLS);
  313. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial, gncParams);
  314. double mu = 1.0;
  315. Vector weights_actual = gnc.calculateWeights(initial, mu);
  316. CHECK(assert_equal(weights_expected, weights_actual, tol));
  317. }
  318. /* ************************************************************************* */
  319. TEST(GncOptimizer, calculateWeightsTLS2) {
  320. // create values
  321. Point2 x_val(0.0, 0.0);
  322. Point2 x_prior(1.0, 0.0);
  323. Values initial;
  324. initial.insert(X(1), x_val);
  325. // create very simple factor graph with a single factor 0.5 * 1/sigma^2 * || x - [1;0] ||^2
  326. double sigma = 1;
  327. SharedDiagonal noise = noiseModel::Diagonal::Sigmas(Vector2(sigma, sigma));
  328. NonlinearFactorGraph nfg;
  329. nfg.add(PriorFactor<Point2>(X(1), x_prior, noise));
  330. // cost of the factor:
  331. DOUBLES_EQUAL(0.5 * 1 / (sigma * sigma), nfg.error(initial), tol);
  332. // check the TLS weights are correct: CASE 1: residual below barcsq
  333. {
  334. // expected:
  335. Vector weights_expected = Vector::Zero(1);
  336. weights_expected[0] = 1.0; // inlier
  337. // actual:
  338. GaussNewtonParams gnParams;
  339. GncParams<GaussNewtonParams> gncParams(gnParams);
  340. gncParams.setLossType(GncLossType::TLS);
  341. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(nfg, initial,
  342. gncParams);
  343. gnc.setInlierCostThresholds(0.51); // if inlier threshold is slightly larger than 0.5, then measurement is inlier
  344. double mu = 1e6;
  345. Vector weights_actual = gnc.calculateWeights(initial, mu);
  346. CHECK(assert_equal(weights_expected, weights_actual, tol));
  347. }
  348. // check the TLS weights are correct: CASE 2: residual above barcsq
  349. {
  350. // expected:
  351. Vector weights_expected = Vector::Zero(1);
  352. weights_expected[0] = 0.0; // outlier
  353. // actual:
  354. GaussNewtonParams gnParams;
  355. GncParams<GaussNewtonParams> gncParams(gnParams);
  356. gncParams.setLossType(GncLossType::TLS);
  357. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(nfg, initial,
  358. gncParams);
  359. gnc.setInlierCostThresholds(0.49); // if inlier threshold is slightly below 0.5, then measurement is outlier
  360. double mu = 1e6; // very large mu recovers original TLS cost
  361. Vector weights_actual = gnc.calculateWeights(initial, mu);
  362. CHECK(assert_equal(weights_expected, weights_actual, tol));
  363. }
  364. // check the TLS weights are correct: CASE 2: residual at barcsq
  365. {
  366. // expected:
  367. Vector weights_expected = Vector::Zero(1);
  368. weights_expected[0] = 0.5; // undecided
  369. // actual:
  370. GaussNewtonParams gnParams;
  371. GncParams<GaussNewtonParams> gncParams(gnParams);
  372. gncParams.setLossType(GncLossType::TLS);
  373. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(nfg, initial,
  374. gncParams);
  375. gnc.setInlierCostThresholds(0.5); // if inlier threshold is slightly below 0.5, then measurement is outlier
  376. double mu = 1e6; // very large mu recovers original TLS cost
  377. Vector weights_actual = gnc.calculateWeights(initial, mu);
  378. CHECK(assert_equal(weights_expected, weights_actual, 1e-5));
  379. }
  380. }
  381. /* ************************************************************************* */
  382. TEST(GncOptimizer, makeWeightedGraph) {
  383. // create original factor
  384. double sigma1 = 0.1;
  385. NonlinearFactorGraph nfg = example::nonlinearFactorGraphWithGivenSigma(
  386. sigma1);
  387. // create expected
  388. double sigma2 = 10;
  389. NonlinearFactorGraph expected = example::nonlinearFactorGraphWithGivenSigma(
  390. sigma2);
  391. // create weights
  392. Vector weights = Vector::Ones(1); // original info:1/0.1^2 = 100. New info: 1/10^2 = 0.01. Ratio is 10-4
  393. weights[0] = 1e-4;
  394. // create actual
  395. Point2 p0(3, 3);
  396. Values initial;
  397. initial.insert(X(1), p0);
  398. LevenbergMarquardtParams lmParams;
  399. GncParams<LevenbergMarquardtParams> gncParams(lmParams);
  400. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(nfg, initial,
  401. gncParams);
  402. NonlinearFactorGraph actual = gnc.makeWeightedGraph(weights);
  403. // check it's all good
  404. CHECK(assert_equal(expected, actual));
  405. }
  406. /* ************************************************************************* */
  407. TEST(GncOptimizer, optimizeSimple) {
  408. auto fg = example::createReallyNonlinearFactorGraph();
  409. Point2 p0(3, 3);
  410. Values initial;
  411. initial.insert(X(1), p0);
  412. LevenbergMarquardtParams lmParams;
  413. GncParams<LevenbergMarquardtParams> gncParams(lmParams);
  414. auto gnc = GncOptimizer<GncParams<LevenbergMarquardtParams>>(fg, initial,
  415. gncParams);
  416. Values actual = gnc.optimize();
  417. DOUBLES_EQUAL(0, fg.error(actual), tol);
  418. }
  419. /* ************************************************************************* */
  420. TEST(GncOptimizer, optimize) {
  421. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  422. Point2 p0(1, 0);
  423. Values initial;
  424. initial.insert(X(1), p0);
  425. // try with nonrobust cost function and standard GN
  426. GaussNewtonParams gnParams;
  427. GaussNewtonOptimizer gn(fg, initial, gnParams);
  428. Values gn_results = gn.optimize();
  429. // converges to incorrect point due to lack of robustness to an outlier, ideal
  430. // solution is Point2(0,0)
  431. CHECK(assert_equal(Point2(0.25, 0.0), gn_results.at<Point2>(X(1)), 1e-3));
  432. // try with robust loss function and standard GN
  433. auto fg_robust = example::sharedRobustFactorGraphWithOutliers(); // same as fg, but with
  434. // factors wrapped in
  435. // Geman McClure losses
  436. GaussNewtonOptimizer gn2(fg_robust, initial, gnParams);
  437. Values gn2_results = gn2.optimize();
  438. // converges to incorrect point, this time due to the nonconvexity of the loss
  439. CHECK(assert_equal(Point2(0.999706, 0.0), gn2_results.at<Point2>(X(1)), 1e-3));
  440. // .. but graduated nonconvexity ensures both robustness and convergence in
  441. // the face of nonconvexity
  442. GncParams<GaussNewtonParams> gncParams(gnParams);
  443. // gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  444. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial, gncParams);
  445. Values gnc_result = gnc.optimize();
  446. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  447. }
  448. /* ************************************************************************* */
  449. TEST(GncOptimizer, optimizeWithKnownInliers) {
  450. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  451. Point2 p0(1, 0);
  452. Values initial;
  453. initial.insert(X(1), p0);
  454. std::vector<size_t> knownInliers;
  455. knownInliers.push_back(0);
  456. knownInliers.push_back(1);
  457. knownInliers.push_back(2);
  458. // nonconvexity with known inliers
  459. {
  460. GncParams<GaussNewtonParams> gncParams;
  461. gncParams.setKnownInliers(knownInliers);
  462. gncParams.setLossType(GncLossType::GM);
  463. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  464. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  465. gncParams);
  466. gnc.setInlierCostThresholds(1.0);
  467. Values gnc_result = gnc.optimize();
  468. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  469. // check weights were actually fixed:
  470. Vector finalWeights = gnc.getWeights();
  471. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  472. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  473. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  474. }
  475. {
  476. GncParams<GaussNewtonParams> gncParams;
  477. gncParams.setKnownInliers(knownInliers);
  478. gncParams.setLossType(GncLossType::TLS);
  479. // gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  480. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  481. gncParams);
  482. Values gnc_result = gnc.optimize();
  483. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  484. // check weights were actually fixed:
  485. Vector finalWeights = gnc.getWeights();
  486. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  487. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  488. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  489. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  490. }
  491. {
  492. // if we set the threshold large, they are all inliers
  493. GncParams<GaussNewtonParams> gncParams;
  494. gncParams.setKnownInliers(knownInliers);
  495. gncParams.setLossType(GncLossType::TLS);
  496. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::VALUES);
  497. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  498. gncParams);
  499. gnc.setInlierCostThresholds(100.0);
  500. Values gnc_result = gnc.optimize();
  501. CHECK(assert_equal(Point2(0.25, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  502. // check weights were actually fixed:
  503. Vector finalWeights = gnc.getWeights();
  504. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  505. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  506. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  507. DOUBLES_EQUAL(1.0, finalWeights[3], tol);
  508. }
  509. }
  510. /* ************************************************************************* */
  511. TEST(GncOptimizer, chi2inv) {
  512. DOUBLES_EQUAL(8.807468393511950, Chi2inv(0.997, 1), tol); // from MATLAB: chi2inv(0.997, 1) = 8.807468393511950
  513. DOUBLES_EQUAL(13.931422665512077, Chi2inv(0.997, 3), tol); // from MATLAB: chi2inv(0.997, 3) = 13.931422665512077
  514. }
  515. /* ************************************************************************* */
  516. TEST(GncOptimizer, barcsq) {
  517. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  518. Point2 p0(1, 0);
  519. Values initial;
  520. initial.insert(X(1), p0);
  521. std::vector<size_t> knownInliers;
  522. knownInliers.push_back(0);
  523. knownInliers.push_back(1);
  524. knownInliers.push_back(2);
  525. GncParams<GaussNewtonParams> gncParams;
  526. gncParams.setKnownInliers(knownInliers);
  527. gncParams.setLossType(GncLossType::GM);
  528. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  529. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  530. gncParams);
  531. // expected: chi2inv(0.99, 2)/2
  532. CHECK(assert_equal(4.605170185988091 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1e-3));
  533. }
  534. /* ************************************************************************* */
  535. TEST(GncOptimizer, barcsq_heterogeneousFactors) {
  536. NonlinearFactorGraph fg;
  537. // specify noise model, otherwise it segfault if we leave default noise model
  538. SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(3, 0.5));
  539. fg.add( PriorFactor<Pose2>( 0, Pose2(0.0, 0.0, 0.0) , model3D )); // size 3
  540. SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(2, 0.5));
  541. fg.add( PriorFactor<Point2>( 1, Point2(0.0,0.0), model2D )); // size 2
  542. SharedNoiseModel model1D(noiseModel::Isotropic::Sigma(1, 0.5));
  543. fg.add( BearingFactor<Pose2, Point2>( 0, 1, 1.0, model1D) ); // size 1
  544. Values initial;
  545. initial.insert(0, Pose2(0.0, 0.0, 0.0));
  546. initial.insert(1, Point2(0.0,0.0));
  547. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial);
  548. CHECK(assert_equal(Vector3(5.672433365072185, 4.605170185988091, 3.317448300510607),
  549. gnc.getInlierCostThresholds(), 1e-3));
  550. // extra test:
  551. // fg.add( PriorFactor<Pose2>( 0, Pose2(0.0, 0.0, 0.0) )); // works if we add model3D as noise model
  552. // std::cout << "fg[3]->dim() " << fg[3]->dim() << std::endl; // this segfaults?
  553. }
  554. /* ************************************************************************* */
  555. TEST(GncOptimizer, setInlierCostThresholds) {
  556. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  557. Point2 p0(1, 0);
  558. Values initial;
  559. initial.insert(X(1), p0);
  560. std::vector<size_t> knownInliers;
  561. knownInliers.push_back(0);
  562. knownInliers.push_back(1);
  563. knownInliers.push_back(2);
  564. {
  565. GncParams<GaussNewtonParams> gncParams;
  566. gncParams.setKnownInliers(knownInliers);
  567. gncParams.setLossType(GncLossType::GM);
  568. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  569. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  570. gncParams);
  571. gnc.setInlierCostThresholds(2.0);
  572. Values gnc_result = gnc.optimize();
  573. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  574. // check weights were actually fixed:
  575. Vector finalWeights = gnc.getWeights();
  576. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  577. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  578. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  579. CHECK(assert_equal(2.0 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1e-3));
  580. }
  581. {
  582. GncParams<GaussNewtonParams> gncParams;
  583. gncParams.setKnownInliers(knownInliers);
  584. gncParams.setLossType(GncLossType::GM);
  585. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  586. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  587. gncParams);
  588. gnc.setInlierCostThresholds(2.0 * Vector::Ones(fg.size()));
  589. Values gnc_result = gnc.optimize();
  590. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  591. // check weights were actually fixed:
  592. Vector finalWeights = gnc.getWeights();
  593. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  594. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  595. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  596. CHECK(assert_equal(2.0 * Vector::Ones(fg.size()), gnc.getInlierCostThresholds(), 1e-3));
  597. }
  598. }
  599. /* ************************************************************************* */
  600. TEST(GncOptimizer, optimizeSmallPoseGraph) {
  601. /// load small pose graph
  602. const string filename = findExampleDataFile("w100.graph");
  603. NonlinearFactorGraph::shared_ptr graph;
  604. Values::shared_ptr initial;
  605. boost::tie(graph, initial) = load2D(filename);
  606. // Add a Gaussian prior on first poses
  607. Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin
  608. SharedDiagonal priorNoise = noiseModel::Diagonal::Sigmas(
  609. Vector3(0.01, 0.01, 0.01));
  610. graph->addPrior(0, priorMean, priorNoise);
  611. /// get expected values by optimizing outlier-free graph
  612. Values expected = LevenbergMarquardtOptimizer(*graph, *initial).optimize();
  613. // add a few outliers
  614. SharedDiagonal betweenNoise = noiseModel::Diagonal::Sigmas(
  615. Vector3(0.1, 0.1, 0.01));
  616. graph->push_back(BetweenFactor<Pose2>(90, 50, Pose2(), betweenNoise)); // some arbitrary and incorrect between factor
  617. /// get expected values by optimizing outlier-free graph
  618. Values expectedWithOutliers = LevenbergMarquardtOptimizer(*graph, *initial)
  619. .optimize();
  620. // as expected, the following test fails due to the presence of an outlier!
  621. // CHECK(assert_equal(expected, expectedWithOutliers, 1e-3));
  622. // GNC
  623. // Note: in difficult instances, we set the odometry measurements to be
  624. // inliers, but this problem is simple enought to succeed even without that
  625. // assumption std::vector<size_t> knownInliers;
  626. GncParams<GaussNewtonParams> gncParams;
  627. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(*graph, *initial,
  628. gncParams);
  629. Values actual = gnc.optimize();
  630. // compare
  631. CHECK(assert_equal(expected, actual, 1e-3)); // yay! we are robust to outliers!
  632. }
  633. /* ************************************************************************* */
  634. TEST(GncOptimizer, knownInliersAndOutliers) {
  635. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  636. Point2 p0(1, 0);
  637. Values initial;
  638. initial.insert(X(1), p0);
  639. // nonconvexity with known inliers and known outliers (check early stopping
  640. // when all measurements are known to be inliers or outliers)
  641. {
  642. std::vector<size_t> knownInliers;
  643. knownInliers.push_back(0);
  644. knownInliers.push_back(1);
  645. knownInliers.push_back(2);
  646. std::vector<size_t> knownOutliers;
  647. knownOutliers.push_back(3);
  648. GncParams<GaussNewtonParams> gncParams;
  649. gncParams.setKnownInliers(knownInliers);
  650. gncParams.setKnownOutliers(knownOutliers);
  651. gncParams.setLossType(GncLossType::GM);
  652. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  653. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  654. gncParams);
  655. gnc.setInlierCostThresholds(1.0);
  656. Values gnc_result = gnc.optimize();
  657. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  658. // check weights were actually fixed:
  659. Vector finalWeights = gnc.getWeights();
  660. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  661. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  662. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  663. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  664. }
  665. // nonconvexity with known inliers and known outliers
  666. {
  667. std::vector<size_t> knownInliers;
  668. knownInliers.push_back(2);
  669. knownInliers.push_back(0);
  670. std::vector<size_t> knownOutliers;
  671. knownOutliers.push_back(3);
  672. GncParams<GaussNewtonParams> gncParams;
  673. gncParams.setKnownInliers(knownInliers);
  674. gncParams.setKnownOutliers(knownOutliers);
  675. gncParams.setLossType(GncLossType::GM);
  676. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  677. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  678. gncParams);
  679. gnc.setInlierCostThresholds(1.0);
  680. Values gnc_result = gnc.optimize();
  681. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  682. // check weights were actually fixed:
  683. Vector finalWeights = gnc.getWeights();
  684. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  685. DOUBLES_EQUAL(1.0, finalWeights[1], 1e-5);
  686. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  687. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  688. }
  689. // only known outliers
  690. {
  691. std::vector<size_t> knownOutliers;
  692. knownOutliers.push_back(3);
  693. GncParams<GaussNewtonParams> gncParams;
  694. gncParams.setKnownOutliers(knownOutliers);
  695. gncParams.setLossType(GncLossType::GM);
  696. //gncParams.setVerbosityGNC(GncParams<GaussNewtonParams>::Verbosity::SUMMARY);
  697. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  698. gncParams);
  699. gnc.setInlierCostThresholds(1.0);
  700. Values gnc_result = gnc.optimize();
  701. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  702. // check weights were actually fixed:
  703. Vector finalWeights = gnc.getWeights();
  704. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  705. DOUBLES_EQUAL(1.0, finalWeights[1], 1e-5);
  706. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  707. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  708. }
  709. }
  710. /* ************************************************************************* */
  711. TEST(GncOptimizer, setWeights) {
  712. auto fg = example::sharedNonRobustFactorGraphWithOutliers();
  713. Point2 p0(1, 0);
  714. Values initial;
  715. initial.insert(X(1), p0);
  716. // initialize weights to be the same
  717. {
  718. GncParams<GaussNewtonParams> gncParams;
  719. gncParams.setLossType(GncLossType::TLS);
  720. Vector weights = 0.5 * Vector::Ones(fg.size());
  721. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  722. gncParams);
  723. gnc.setWeights(weights);
  724. gnc.setInlierCostThresholds(1.0);
  725. Values gnc_result = gnc.optimize();
  726. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  727. // check weights were actually fixed:
  728. Vector finalWeights = gnc.getWeights();
  729. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  730. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  731. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  732. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  733. }
  734. // try a more challenging initialization
  735. {
  736. GncParams<GaussNewtonParams> gncParams;
  737. gncParams.setLossType(GncLossType::TLS);
  738. Vector weights = Vector::Zero(fg.size());
  739. weights(2) = 1.0;
  740. weights(3) = 1.0; // bad initialization: we say the outlier is inlier
  741. // GNC can still recover (but if you omit weights(2) = 1.0, then it would fail)
  742. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  743. gncParams);
  744. gnc.setWeights(weights);
  745. gnc.setInlierCostThresholds(1.0);
  746. Values gnc_result = gnc.optimize();
  747. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  748. // check weights were actually fixed:
  749. Vector finalWeights = gnc.getWeights();
  750. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  751. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  752. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  753. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  754. }
  755. // initialize weights and also set known inliers/outliers
  756. {
  757. GncParams<GaussNewtonParams> gncParams;
  758. std::vector<size_t> knownInliers;
  759. knownInliers.push_back(2);
  760. knownInliers.push_back(0);
  761. std::vector<size_t> knownOutliers;
  762. knownOutliers.push_back(3);
  763. gncParams.setKnownInliers(knownInliers);
  764. gncParams.setKnownOutliers(knownOutliers);
  765. gncParams.setLossType(GncLossType::TLS);
  766. Vector weights = 0.5 * Vector::Ones(fg.size());
  767. auto gnc = GncOptimizer<GncParams<GaussNewtonParams>>(fg, initial,
  768. gncParams);
  769. gnc.setWeights(weights);
  770. gnc.setInlierCostThresholds(1.0);
  771. Values gnc_result = gnc.optimize();
  772. CHECK(assert_equal(Point2(0.0, 0.0), gnc_result.at<Point2>(X(1)), 1e-3));
  773. // check weights were actually fixed:
  774. Vector finalWeights = gnc.getWeights();
  775. DOUBLES_EQUAL(1.0, finalWeights[0], tol);
  776. DOUBLES_EQUAL(1.0, finalWeights[1], tol);
  777. DOUBLES_EQUAL(1.0, finalWeights[2], tol);
  778. DOUBLES_EQUAL(0.0, finalWeights[3], tol);
  779. }
  780. }
  781. /* ************************************************************************* */
  782. int main() {
  783. TestResult tr;
  784. return TestRegistry::runAllTests(tr);
  785. }
  786. /* ************************************************************************* */