testNonlinearOptimizer.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670
  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 testNonlinearOptimizer.cpp
  10. * @brief Unit tests for NonlinearOptimizer class
  11. * @author Frank Dellaert
  12. */
  13. #include <tests/smallExample.h>
  14. #include <gtsam/slam/BetweenFactor.h>
  15. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  16. #include <gtsam/nonlinear/Values.h>
  17. #include <gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h>
  18. #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
  19. #include <gtsam/nonlinear/DoglegOptimizer.h>
  20. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  21. #include <gtsam/linear/GaussianFactorGraph.h>
  22. #include <gtsam/linear/NoiseModel.h>
  23. #include <gtsam/inference/Symbol.h>
  24. #include <gtsam/geometry/Pose2.h>
  25. #include <gtsam/base/Matrix.h>
  26. #include <CppUnitLite/TestHarness.h>
  27. #include <boost/range/adaptor/map.hpp>
  28. #include <boost/shared_ptr.hpp>
  29. #include <boost/assign/std/list.hpp> // for operator +=
  30. using namespace boost::assign;
  31. using boost::adaptors::map_values;
  32. #include <iostream>
  33. #include <fstream>
  34. using namespace std;
  35. using namespace gtsam;
  36. const double tol = 1e-5;
  37. using symbol_shorthand::X;
  38. using symbol_shorthand::L;
  39. /* ************************************************************************* */
  40. TEST( NonlinearOptimizer, paramsEquals )
  41. {
  42. // default constructors lead to two identical params
  43. GaussNewtonParams gnParams1;
  44. GaussNewtonParams gnParams2;
  45. CHECK(gnParams1.equals(gnParams2));
  46. // but the params become different if we change something in gnParams2
  47. gnParams2.setVerbosity("DELTA");
  48. CHECK(!gnParams1.equals(gnParams2));
  49. }
  50. /* ************************************************************************* */
  51. TEST( NonlinearOptimizer, iterateLM )
  52. {
  53. // really non-linear factor graph
  54. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  55. // config far from minimum
  56. Point2 x0(3,0);
  57. Values config;
  58. config.insert(X(1), x0);
  59. // normal iterate
  60. GaussNewtonParams gnParams;
  61. GaussNewtonOptimizer gnOptimizer(fg, config, gnParams);
  62. gnOptimizer.iterate();
  63. // LM iterate with lambda 0 should be the same
  64. LevenbergMarquardtParams lmParams;
  65. lmParams.lambdaInitial = 0.0;
  66. LevenbergMarquardtOptimizer lmOptimizer(fg, config, lmParams);
  67. lmOptimizer.iterate();
  68. CHECK(assert_equal(gnOptimizer.values(), lmOptimizer.values(), 1e-9));
  69. }
  70. /* ************************************************************************* */
  71. TEST( NonlinearOptimizer, optimize )
  72. {
  73. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  74. // test error at minimum
  75. Point2 xstar(0,0);
  76. Values cstar;
  77. cstar.insert(X(1), xstar);
  78. DOUBLES_EQUAL(0.0,fg.error(cstar),0.0);
  79. // test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
  80. Point2 x0(3,3);
  81. Values c0;
  82. c0.insert(X(1), x0);
  83. DOUBLES_EQUAL(199.0,fg.error(c0),1e-3);
  84. // optimize parameters
  85. Ordering ord;
  86. ord.push_back(X(1));
  87. // Gauss-Newton
  88. GaussNewtonParams gnParams;
  89. gnParams.ordering = ord;
  90. Values actual1 = GaussNewtonOptimizer(fg, c0, gnParams).optimize();
  91. DOUBLES_EQUAL(0,fg.error(actual1),tol);
  92. // Levenberg-Marquardt
  93. LevenbergMarquardtParams lmParams;
  94. lmParams.ordering = ord;
  95. Values actual2 = LevenbergMarquardtOptimizer(fg, c0, lmParams).optimize();
  96. DOUBLES_EQUAL(0,fg.error(actual2),tol);
  97. // Dogleg
  98. DoglegParams dlParams;
  99. dlParams.ordering = ord;
  100. Values actual3 = DoglegOptimizer(fg, c0, dlParams).optimize();
  101. DOUBLES_EQUAL(0,fg.error(actual3),tol);
  102. }
  103. /* ************************************************************************* */
  104. TEST( NonlinearOptimizer, SimpleLMOptimizer )
  105. {
  106. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  107. Point2 x0(3,3);
  108. Values c0;
  109. c0.insert(X(1), x0);
  110. Values actual = LevenbergMarquardtOptimizer(fg, c0).optimize();
  111. DOUBLES_EQUAL(0,fg.error(actual),tol);
  112. }
  113. /* ************************************************************************* */
  114. TEST( NonlinearOptimizer, SimpleGNOptimizer )
  115. {
  116. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  117. Point2 x0(3,3);
  118. Values c0;
  119. c0.insert(X(1), x0);
  120. Values actual = GaussNewtonOptimizer(fg, c0).optimize();
  121. DOUBLES_EQUAL(0,fg.error(actual),tol);
  122. }
  123. /* ************************************************************************* */
  124. TEST( NonlinearOptimizer, SimpleDLOptimizer )
  125. {
  126. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  127. Point2 x0(3,3);
  128. Values c0;
  129. c0.insert(X(1), x0);
  130. Values actual = DoglegOptimizer(fg, c0).optimize();
  131. DOUBLES_EQUAL(0,fg.error(actual),tol);
  132. }
  133. /* ************************************************************************* */
  134. TEST( NonlinearOptimizer, optimization_method )
  135. {
  136. LevenbergMarquardtParams paramsQR;
  137. paramsQR.linearSolverType = LevenbergMarquardtParams::MULTIFRONTAL_QR;
  138. LevenbergMarquardtParams paramsChol;
  139. paramsChol.linearSolverType = LevenbergMarquardtParams::MULTIFRONTAL_CHOLESKY;
  140. NonlinearFactorGraph fg = example::createReallyNonlinearFactorGraph();
  141. Point2 x0(3,3);
  142. Values c0;
  143. c0.insert(X(1), x0);
  144. Values actualMFQR = LevenbergMarquardtOptimizer(fg, c0, paramsQR).optimize();
  145. DOUBLES_EQUAL(0,fg.error(actualMFQR),tol);
  146. Values actualMFChol = LevenbergMarquardtOptimizer(fg, c0, paramsChol).optimize();
  147. DOUBLES_EQUAL(0,fg.error(actualMFChol),tol);
  148. }
  149. /* ************************************************************************* */
  150. TEST( NonlinearOptimizer, Factorization )
  151. {
  152. Values config;
  153. config.insert(X(1), Pose2(0.,0.,0.));
  154. config.insert(X(2), Pose2(1.5,0.,0.));
  155. NonlinearFactorGraph graph;
  156. graph.addPrior(X(1), Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3, 1e-10));
  157. graph += BetweenFactor<Pose2>(X(1),X(2), Pose2(1.,0.,0.), noiseModel::Isotropic::Sigma(3, 1));
  158. Ordering ordering;
  159. ordering.push_back(X(1));
  160. ordering.push_back(X(2));
  161. LevenbergMarquardtParams params;
  162. LevenbergMarquardtParams::SetLegacyDefaults(&params);
  163. LevenbergMarquardtOptimizer optimizer(graph, config, ordering, params);
  164. optimizer.iterate();
  165. Values expected;
  166. expected.insert(X(1), Pose2(0.,0.,0.));
  167. expected.insert(X(2), Pose2(1.,0.,0.));
  168. CHECK(assert_equal(expected, optimizer.values(), 1e-5));
  169. }
  170. /* ************************************************************************* */
  171. TEST(NonlinearOptimizer, NullFactor) {
  172. NonlinearFactorGraph fg = example::createReallyNonlinearFactorGraph();
  173. // Add null factor
  174. fg.push_back(NonlinearFactorGraph::sharedFactor());
  175. // test error at minimum
  176. Point2 xstar(0,0);
  177. Values cstar;
  178. cstar.insert(X(1), xstar);
  179. DOUBLES_EQUAL(0.0,fg.error(cstar),0.0);
  180. // test error at initial = [(1-cos(3))^2 + (sin(3))^2]*50 =
  181. Point2 x0(3,3);
  182. Values c0;
  183. c0.insert(X(1), x0);
  184. DOUBLES_EQUAL(199.0,fg.error(c0),1e-3);
  185. // optimize parameters
  186. Ordering ord;
  187. ord.push_back(X(1));
  188. // Gauss-Newton
  189. Values actual1 = GaussNewtonOptimizer(fg, c0, ord).optimize();
  190. DOUBLES_EQUAL(0,fg.error(actual1),tol);
  191. // Levenberg-Marquardt
  192. Values actual2 = LevenbergMarquardtOptimizer(fg, c0, ord).optimize();
  193. DOUBLES_EQUAL(0,fg.error(actual2),tol);
  194. // Dogleg
  195. Values actual3 = DoglegOptimizer(fg, c0, ord).optimize();
  196. DOUBLES_EQUAL(0,fg.error(actual3),tol);
  197. }
  198. /* ************************************************************************* */
  199. TEST_UNSAFE(NonlinearOptimizer, MoreOptimization) {
  200. NonlinearFactorGraph fg;
  201. fg.addPrior(0, Pose2(0, 0, 0), noiseModel::Isotropic::Sigma(3, 1));
  202. fg += BetweenFactor<Pose2>(0, 1, Pose2(1, 0, M_PI / 2),
  203. noiseModel::Isotropic::Sigma(3, 1));
  204. fg += BetweenFactor<Pose2>(1, 2, Pose2(1, 0, M_PI / 2),
  205. noiseModel::Isotropic::Sigma(3, 1));
  206. Values init;
  207. init.insert(0, Pose2(3, 4, -M_PI));
  208. init.insert(1, Pose2(10, 2, -M_PI));
  209. init.insert(2, Pose2(11, 7, -M_PI));
  210. Values expected;
  211. expected.insert(0, Pose2(0, 0, 0));
  212. expected.insert(1, Pose2(1, 0, M_PI / 2));
  213. expected.insert(2, Pose2(1, 1, M_PI));
  214. VectorValues expectedGradient;
  215. expectedGradient.insert(0,Z_3x1);
  216. expectedGradient.insert(1,Z_3x1);
  217. expectedGradient.insert(2,Z_3x1);
  218. // Try LM and Dogleg
  219. LevenbergMarquardtParams params = LevenbergMarquardtParams::LegacyDefaults();
  220. {
  221. LevenbergMarquardtOptimizer optimizer(fg, init, params);
  222. // test convergence
  223. Values actual = optimizer.optimize();
  224. EXPECT(assert_equal(expected, actual));
  225. // Check that the gradient is zero
  226. GaussianFactorGraph::shared_ptr linear = optimizer.linearize();
  227. EXPECT(assert_equal(expectedGradient,linear->gradientAtZero()));
  228. }
  229. EXPECT(assert_equal(expected, DoglegOptimizer(fg, init).optimize()));
  230. // cout << "===================================================================================" << endl;
  231. // Try LM with diagonal damping
  232. Values initBetter;
  233. initBetter.insert(0, Pose2(3,4,0));
  234. initBetter.insert(1, Pose2(10,2,M_PI/3));
  235. initBetter.insert(2, Pose2(11,7,M_PI/2));
  236. {
  237. params.diagonalDamping = true;
  238. LevenbergMarquardtOptimizer optimizer(fg, initBetter, params);
  239. // test the diagonal
  240. GaussianFactorGraph::shared_ptr linear = optimizer.linearize();
  241. VectorValues d = linear->hessianDiagonal();
  242. VectorValues sqrtHessianDiagonal = d;
  243. for (Vector& v : sqrtHessianDiagonal | map_values) v = v.cwiseSqrt();
  244. GaussianFactorGraph damped = optimizer.buildDampedSystem(*linear, sqrtHessianDiagonal);
  245. VectorValues expectedDiagonal = d + params.lambdaInitial * d;
  246. EXPECT(assert_equal(expectedDiagonal, damped.hessianDiagonal()));
  247. // test convergence (does not!)
  248. Values actual = optimizer.optimize();
  249. EXPECT(assert_equal(expected, actual));
  250. // Check that the gradient is zero (it is not!)
  251. linear = optimizer.linearize();
  252. EXPECT(assert_equal(expectedGradient,linear->gradientAtZero()));
  253. // Check that the gradient is zero for damped system (it is not!)
  254. damped = optimizer.buildDampedSystem(*linear, sqrtHessianDiagonal);
  255. VectorValues actualGradient = damped.gradientAtZero();
  256. EXPECT(assert_equal(expectedGradient,actualGradient));
  257. /* This block was made to test the original initial guess "init"
  258. // Check errors at convergence and errors in direction of gradient (decreases!)
  259. EXPECT_DOUBLES_EQUAL(46.02558,fg.error(actual),1e-5);
  260. EXPECT_DOUBLES_EQUAL(44.742237,fg.error(actual.retract(-0.01*actualGradient)),1e-5);
  261. // Check that solve yields gradient (it's not equal to gradient, as predicted)
  262. VectorValues delta = damped.optimize();
  263. double factor = actualGradient[0][0]/delta[0][0];
  264. EXPECT(assert_equal(actualGradient,factor*delta));
  265. // Still pointing downhill wrt actual gradient !
  266. EXPECT_DOUBLES_EQUAL( 0.1056157,dot(-1*actualGradient,delta),1e-3);
  267. // delta.print("This is the delta value computed by LM with diagonal damping");
  268. // Still pointing downhill wrt expected gradient (IT DOES NOT! actually they are perpendicular)
  269. EXPECT_DOUBLES_EQUAL( 0.0,dot(-1*expectedGradient,delta),1e-5);
  270. // Check errors at convergence and errors in direction of solution (does not decrease!)
  271. EXPECT_DOUBLES_EQUAL(46.0254859,fg.error(actual.retract(delta)),1e-5);
  272. // Check errors at convergence and errors at a small step in direction of solution (does not decrease!)
  273. EXPECT_DOUBLES_EQUAL(46.0255,fg.error(actual.retract(0.01*delta)),1e-3);
  274. */
  275. }
  276. }
  277. /* ************************************************************************* */
  278. TEST(NonlinearOptimizer, Pose2OptimizationWithHuberNoOutlier) {
  279. NonlinearFactorGraph fg;
  280. fg.addPrior(0, Pose2(0,0,0), noiseModel::Isotropic::Sigma(3,1));
  281. fg += BetweenFactor<Pose2>(0, 1, Pose2(1,1.1,M_PI/4),
  282. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(2.0),
  283. noiseModel::Isotropic::Sigma(3,1)));
  284. fg += BetweenFactor<Pose2>(0, 1, Pose2(1,0.9,M_PI/2),
  285. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(3.0),
  286. noiseModel::Isotropic::Sigma(3,1)));
  287. Values init;
  288. init.insert(0, Pose2(0,0,0));
  289. init.insert(1, Pose2(0.961187, 0.99965, 1.1781));
  290. Values expected;
  291. expected.insert(0, Pose2(0,0,0));
  292. expected.insert(1, Pose2(0.961187, 0.99965, 1.1781));
  293. LevenbergMarquardtParams lm_params;
  294. auto gn_result = GaussNewtonOptimizer(fg, init).optimize();
  295. auto lm_result = LevenbergMarquardtOptimizer(fg, init, lm_params).optimize();
  296. auto dl_result = DoglegOptimizer(fg, init).optimize();
  297. EXPECT(assert_equal(expected, gn_result, 3e-2));
  298. EXPECT(assert_equal(expected, lm_result, 3e-2));
  299. EXPECT(assert_equal(expected, dl_result, 3e-2));
  300. }
  301. /* ************************************************************************* */
  302. TEST(NonlinearOptimizer, Point2LinearOptimizationWithHuber) {
  303. NonlinearFactorGraph fg;
  304. fg.addPrior(0, Point2(0,0), noiseModel::Isotropic::Sigma(2,0.01));
  305. fg += BetweenFactor<Point2>(0, 1, Point2(1,1.8),
  306. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.0),
  307. noiseModel::Isotropic::Sigma(2,1)));
  308. fg += BetweenFactor<Point2>(0, 1, Point2(1,0.9),
  309. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.0),
  310. noiseModel::Isotropic::Sigma(2,1)));
  311. fg += BetweenFactor<Point2>(0, 1, Point2(1,90),
  312. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.0),
  313. noiseModel::Isotropic::Sigma(2,1)));
  314. Values init;
  315. init.insert(0, Point2(1,1));
  316. init.insert(1, Point2(1,0));
  317. Values expected;
  318. expected.insert(0, Point2(0,0));
  319. expected.insert(1, Point2(1,1.85));
  320. LevenbergMarquardtParams params;
  321. auto gn_result = GaussNewtonOptimizer(fg, init).optimize();
  322. auto lm_result = LevenbergMarquardtOptimizer(fg, init, params).optimize();
  323. auto dl_result = DoglegOptimizer(fg, init).optimize();
  324. EXPECT(assert_equal(expected, gn_result, 1e-4));
  325. EXPECT(assert_equal(expected, lm_result, 1e-4));
  326. EXPECT(assert_equal(expected, dl_result, 1e-4));
  327. }
  328. /* ************************************************************************* */
  329. TEST(NonlinearOptimizer, Pose2OptimizationWithHuber) {
  330. NonlinearFactorGraph fg;
  331. fg.addPrior(0, Pose2(0,0, 0), noiseModel::Isotropic::Sigma(3,0.1));
  332. fg += BetweenFactor<Pose2>(0, 1, Pose2(0,9, M_PI/2),
  333. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(0.2),
  334. noiseModel::Isotropic::Sigma(3,1)));
  335. fg += BetweenFactor<Pose2>(0, 1, Pose2(0, 11, M_PI/2),
  336. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(0.2),
  337. noiseModel::Isotropic::Sigma(3,1)));
  338. fg += BetweenFactor<Pose2>(0, 1, Pose2(0, 10, M_PI/2),
  339. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(0.2),
  340. noiseModel::Isotropic::Sigma(3,1)));
  341. fg += BetweenFactor<Pose2>(0, 1, Pose2(0,9, 0),
  342. noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(0.2),
  343. noiseModel::Isotropic::Sigma(3,1)));
  344. Values init;
  345. init.insert(0, Pose2(0, 0, 0));
  346. init.insert(1, Pose2(0, 10, M_PI/4));
  347. Values expected;
  348. expected.insert(0, Pose2(0, 0, 0));
  349. expected.insert(1, Pose2(0, 10, 1.45212));
  350. LevenbergMarquardtParams params;
  351. auto gn_result = GaussNewtonOptimizer(fg, init).optimize();
  352. auto lm_result = LevenbergMarquardtOptimizer(fg, init, params).optimize();
  353. auto dl_result = DoglegOptimizer(fg, init).optimize();
  354. EXPECT(assert_equal(expected, gn_result, 1e-1));
  355. EXPECT(assert_equal(expected, lm_result, 1e-1));
  356. EXPECT(assert_equal(expected, dl_result, 1e-1));
  357. }
  358. /* ************************************************************************* */
  359. TEST(NonlinearOptimizer, RobustMeanCalculation) {
  360. NonlinearFactorGraph fg;
  361. Values init;
  362. Values expected;
  363. auto huber = noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(20),
  364. noiseModel::Isotropic::Sigma(1, 1));
  365. vector<double> pts{-10,-3,-1,1,3,10,1000};
  366. for(auto pt : pts) {
  367. fg.addPrior(0, pt, huber);
  368. }
  369. init.insert(0, 100.0);
  370. expected.insert(0, 3.33333333);
  371. DoglegParams params_dl;
  372. params_dl.setRelativeErrorTol(1e-10);
  373. auto gn_result = GaussNewtonOptimizer(fg, init).optimize();
  374. auto lm_result = LevenbergMarquardtOptimizer(fg, init).optimize();
  375. auto dl_result = DoglegOptimizer(fg, init, params_dl).optimize();
  376. EXPECT(assert_equal(expected, gn_result, tol));
  377. EXPECT(assert_equal(expected, lm_result, tol));
  378. EXPECT(assert_equal(expected, dl_result, tol));
  379. }
  380. /* ************************************************************************* */
  381. TEST(NonlinearOptimizer, disconnected_graph) {
  382. Values expected;
  383. expected.insert(X(1), Pose2(0.,0.,0.));
  384. expected.insert(X(2), Pose2(1.5,0.,0.));
  385. expected.insert(X(3), Pose2(3.0,0.,0.));
  386. Values init;
  387. init.insert(X(1), Pose2(0.,0.,0.));
  388. init.insert(X(2), Pose2(0.,0.,0.));
  389. init.insert(X(3), Pose2(0.,0.,0.));
  390. NonlinearFactorGraph graph;
  391. graph.addPrior(X(1), Pose2(0.,0.,0.), noiseModel::Isotropic::Sigma(3,1));
  392. graph += BetweenFactor<Pose2>(X(1),X(2), Pose2(1.5,0.,0.), noiseModel::Isotropic::Sigma(3,1));
  393. graph.addPrior(X(3), Pose2(3.,0.,0.), noiseModel::Isotropic::Sigma(3,1));
  394. EXPECT(assert_equal(expected, LevenbergMarquardtOptimizer(graph, init).optimize()));
  395. }
  396. /* ************************************************************************* */
  397. #include <gtsam/linear/iterative.h>
  398. class IterativeLM : public LevenbergMarquardtOptimizer {
  399. /// Solver specific parameters
  400. ConjugateGradientParameters cgParams_;
  401. Values initial_;
  402. public:
  403. /// Constructor
  404. IterativeLM(const NonlinearFactorGraph& graph, const Values& initialValues,
  405. const ConjugateGradientParameters& p,
  406. const LevenbergMarquardtParams& params =
  407. LevenbergMarquardtParams::LegacyDefaults())
  408. : LevenbergMarquardtOptimizer(graph, initialValues, params),
  409. cgParams_(p),
  410. initial_(initialValues) {}
  411. /// Solve that uses conjugate gradient
  412. VectorValues solve(const GaussianFactorGraph& gfg,
  413. const NonlinearOptimizerParams& params) const override {
  414. VectorValues zeros = initial_.zeroVectors();
  415. return conjugateGradientDescent(gfg, zeros, cgParams_);
  416. }
  417. };
  418. /* ************************************************************************* */
  419. TEST(NonlinearOptimizer, subclass_solver) {
  420. Values expected;
  421. expected.insert(X(1), Pose2(0., 0., 0.));
  422. expected.insert(X(2), Pose2(1.5, 0., 0.));
  423. expected.insert(X(3), Pose2(3.0, 0., 0.));
  424. Values init;
  425. init.insert(X(1), Pose2(0., 0., 0.));
  426. init.insert(X(2), Pose2(0., 0., 0.));
  427. init.insert(X(3), Pose2(0., 0., 0.));
  428. NonlinearFactorGraph graph;
  429. graph.addPrior(X(1), Pose2(0., 0., 0.), noiseModel::Isotropic::Sigma(3, 1));
  430. graph += BetweenFactor<Pose2>(X(1), X(2), Pose2(1.5, 0., 0.),
  431. noiseModel::Isotropic::Sigma(3, 1));
  432. graph.addPrior(X(3), Pose2(3., 0., 0.), noiseModel::Isotropic::Sigma(3, 1));
  433. ConjugateGradientParameters p;
  434. Values actual = IterativeLM(graph, init, p).optimize();
  435. EXPECT(assert_equal(expected, actual, 1e-4));
  436. }
  437. /* ************************************************************************* */
  438. TEST( NonlinearOptimizer, logfile )
  439. {
  440. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  441. Point2 x0(3,3);
  442. Values c0;
  443. c0.insert(X(1), x0);
  444. // Levenberg-Marquardt
  445. LevenbergMarquardtParams lmParams;
  446. static const string filename("testNonlinearOptimizer.log");
  447. lmParams.logFile = filename;
  448. LevenbergMarquardtOptimizer(fg, c0, lmParams).optimize();
  449. // stringstream expected,actual;
  450. // ifstream ifs(("../../gtsam/tests/" + filename).c_str());
  451. // if(!ifs) throw std::runtime_error(filename);
  452. // expected << ifs.rdbuf();
  453. // ifs.close();
  454. // ifstream ifs2(filename.c_str());
  455. // if(!ifs2) throw std::runtime_error(filename);
  456. // actual << ifs2.rdbuf();
  457. // EXPECT(actual.str()==expected.str());
  458. }
  459. /* ************************************************************************* */
  460. TEST( NonlinearOptimizer, iterationHook_LM )
  461. {
  462. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  463. Point2 x0(3,3);
  464. Values c0;
  465. c0.insert(X(1), x0);
  466. // Levenberg-Marquardt
  467. LevenbergMarquardtParams lmParams;
  468. size_t lastIterCalled = 0;
  469. lmParams.iterationHook = [&](size_t iteration, double oldError, double newError)
  470. {
  471. // Tests:
  472. lastIterCalled = iteration;
  473. EXPECT(newError<oldError);
  474. // Example of evolution printout:
  475. //std::cout << "iter: " << iteration << " error: " << oldError << " => " << newError <<"\n";
  476. };
  477. LevenbergMarquardtOptimizer(fg, c0, lmParams).optimize();
  478. EXPECT(lastIterCalled>5);
  479. }
  480. /* ************************************************************************* */
  481. TEST( NonlinearOptimizer, iterationHook_CG )
  482. {
  483. NonlinearFactorGraph fg(example::createReallyNonlinearFactorGraph());
  484. Point2 x0(3,3);
  485. Values c0;
  486. c0.insert(X(1), x0);
  487. // Levenberg-Marquardt
  488. NonlinearConjugateGradientOptimizer::Parameters cgParams;
  489. size_t lastIterCalled = 0;
  490. cgParams.iterationHook = [&](size_t iteration, double oldError, double newError)
  491. {
  492. // Tests:
  493. lastIterCalled = iteration;
  494. EXPECT(newError<oldError);
  495. // Example of evolution printout:
  496. //std::cout << "iter: " << iteration << " error: " << oldError << " => " << newError <<"\n";
  497. };
  498. NonlinearConjugateGradientOptimizer(fg, c0, cgParams).optimize();
  499. EXPECT(lastIterCalled>5);
  500. }
  501. /* ************************************************************************* */
  502. //// Minimal traits example
  503. struct MyType : public Vector3 {
  504. using Vector3::Vector3;
  505. };
  506. namespace gtsam {
  507. template <>
  508. struct traits<MyType> {
  509. static bool Equals(const MyType& a, const MyType& b, double tol) {
  510. return (a - b).array().abs().maxCoeff() < tol;
  511. }
  512. static void Print(const MyType&, const string&) {}
  513. static int GetDimension(const MyType&) { return 3; }
  514. static MyType Retract(const MyType& a, const Vector3& b) { return a + b; }
  515. static Vector3 Local(const MyType& a, const MyType& b) { return b - a; }
  516. };
  517. }
  518. TEST(NonlinearOptimizer, Traits) {
  519. NonlinearFactorGraph fg;
  520. fg.addPrior(0, MyType(0, 0, 0), noiseModel::Isotropic::Sigma(3, 1));
  521. Values init;
  522. init.insert(0, MyType(0,0,0));
  523. LevenbergMarquardtOptimizer optimizer(fg, init);
  524. Values actual = optimizer.optimize();
  525. EXPECT(assert_equal(init, actual));
  526. }
  527. /* ************************************************************************* */
  528. int main() {
  529. TestResult tr;
  530. return TestRegistry::runAllTests(tr);
  531. }
  532. /* ************************************************************************* */