testNonlinearEquality.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587
  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 testNonlinearEquality.cpp
  10. * @author Alex Cunningham
  11. */
  12. #include <tests/simulated2DConstraints.h>
  13. #include <gtsam/nonlinear/PriorFactor.h>
  14. #include <gtsam/slam/ProjectionFactor.h>
  15. #include <gtsam/nonlinear/NonlinearEquality.h>
  16. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  17. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  18. #include <gtsam/linear/GaussianBayesNet.h>
  19. #include <gtsam/inference/Symbol.h>
  20. #include <gtsam/geometry/Point2.h>
  21. #include <gtsam/geometry/Pose2.h>
  22. #include <gtsam/geometry/Point3.h>
  23. #include <gtsam/geometry/Pose3.h>
  24. #include <gtsam/geometry/Cal3_S2.h>
  25. #include <gtsam/geometry/PinholeCamera.h>
  26. #include <CppUnitLite/TestHarness.h>
  27. using namespace std;
  28. using namespace gtsam;
  29. namespace eq2D = simulated2D::equality_constraints;
  30. static const double tol = 1e-5;
  31. typedef PriorFactor<Pose2> PosePrior;
  32. typedef NonlinearEquality<Pose2> PoseNLE;
  33. typedef boost::shared_ptr<PoseNLE> shared_poseNLE;
  34. static Symbol key('x', 1);
  35. //******************************************************************************
  36. TEST ( NonlinearEquality, linearization ) {
  37. Pose2 value = Pose2(2.1, 1.0, 2.0);
  38. Values linearize;
  39. linearize.insert(key, value);
  40. // create a nonlinear equality constraint
  41. shared_poseNLE nle(new PoseNLE(key, value));
  42. // check linearize
  43. SharedDiagonal constraintModel = noiseModel::Constrained::All(3);
  44. JacobianFactor expLF(key, I_3x3, Z_3x1, constraintModel);
  45. GaussianFactor::shared_ptr actualLF = nle->linearize(linearize);
  46. EXPECT(assert_equal((const GaussianFactor&)expLF, *actualLF));
  47. }
  48. //******************************************************************************
  49. TEST ( NonlinearEquality, linearization_pose ) {
  50. Symbol key('x', 1);
  51. Pose2 value;
  52. Values config;
  53. config.insert(key, value);
  54. // create a nonlinear equality constraint
  55. shared_poseNLE nle(new PoseNLE(key, value));
  56. GaussianFactor::shared_ptr actualLF = nle->linearize(config);
  57. EXPECT(true);
  58. }
  59. //******************************************************************************
  60. TEST ( NonlinearEquality, linearization_fail ) {
  61. Pose2 value = Pose2(2.1, 1.0, 2.0);
  62. Pose2 wrong = Pose2(2.1, 3.0, 4.0);
  63. Values bad_linearize;
  64. bad_linearize.insert(key, wrong);
  65. // create a nonlinear equality constraint
  66. shared_poseNLE nle(new PoseNLE(key, value));
  67. // check linearize to ensure that it fails for bad linearization points
  68. CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
  69. }
  70. //******************************************************************************
  71. TEST ( NonlinearEquality, linearization_fail_pose ) {
  72. Symbol key('x', 1);
  73. Pose2 value(2.0, 1.0, 2.0), wrong(2.0, 3.0, 4.0);
  74. Values bad_linearize;
  75. bad_linearize.insert(key, wrong);
  76. // create a nonlinear equality constraint
  77. shared_poseNLE nle(new PoseNLE(key, value));
  78. // check linearize to ensure that it fails for bad linearization points
  79. CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
  80. }
  81. //******************************************************************************
  82. TEST ( NonlinearEquality, linearization_fail_pose_origin ) {
  83. Symbol key('x', 1);
  84. Pose2 value, wrong(2.0, 3.0, 4.0);
  85. Values bad_linearize;
  86. bad_linearize.insert(key, wrong);
  87. // create a nonlinear equality constraint
  88. shared_poseNLE nle(new PoseNLE(key, value));
  89. // check linearize to ensure that it fails for bad linearization points
  90. CHECK_EXCEPTION(nle->linearize(bad_linearize), std::invalid_argument);
  91. }
  92. //******************************************************************************
  93. TEST ( NonlinearEquality, error ) {
  94. Pose2 value = Pose2(2.1, 1.0, 2.0);
  95. Pose2 wrong = Pose2(2.1, 3.0, 4.0);
  96. Values feasible, bad_linearize;
  97. feasible.insert(key, value);
  98. bad_linearize.insert(key, wrong);
  99. // create a nonlinear equality constraint
  100. shared_poseNLE nle(new PoseNLE(key, value));
  101. // check error function outputs
  102. Vector actual = nle->unwhitenedError(feasible);
  103. EXPECT(assert_equal(actual, Z_3x1));
  104. actual = nle->unwhitenedError(bad_linearize);
  105. EXPECT(
  106. assert_equal(actual, Vector::Constant(3, std::numeric_limits<double>::infinity())));
  107. }
  108. //******************************************************************************
  109. TEST ( NonlinearEquality, equals ) {
  110. Pose2 value1 = Pose2(2.1, 1.0, 2.0);
  111. Pose2 value2 = Pose2(2.1, 3.0, 4.0);
  112. // create some constraints to compare
  113. shared_poseNLE nle1(new PoseNLE(key, value1));
  114. shared_poseNLE nle2(new PoseNLE(key, value1));
  115. shared_poseNLE nle3(new PoseNLE(key, value2));
  116. // verify
  117. EXPECT(nle1->equals(*nle2));
  118. // basic equality = true
  119. EXPECT(nle2->equals(*nle1));
  120. // test symmetry of equals()
  121. EXPECT(!nle1->equals(*nle3));
  122. // test config
  123. }
  124. //******************************************************************************
  125. TEST ( NonlinearEquality, allow_error_pose ) {
  126. Symbol key1('x', 1);
  127. Pose2 feasible1(1.0, 2.0, 3.0);
  128. double error_gain = 500.0;
  129. PoseNLE nle(key1, feasible1, error_gain);
  130. // the unwhitened error should provide logmap to the feasible state
  131. Pose2 badPoint1(0.0, 2.0, 3.0);
  132. Vector actVec = nle.evaluateError(badPoint1);
  133. Vector expVec = Vector3(-0.989992, -0.14112, 0.0);
  134. EXPECT(assert_equal(expVec, actVec, 1e-5));
  135. // the actual error should have a gain on it
  136. Values config;
  137. config.insert(key1, badPoint1);
  138. double actError = nle.error(config);
  139. DOUBLES_EQUAL(500.0, actError, 1e-9);
  140. // check linearization
  141. GaussianFactor::shared_ptr actLinFactor = nle.linearize(config);
  142. Matrix A1 = I_3x3;
  143. Vector b = expVec;
  144. SharedDiagonal model = noiseModel::Constrained::All(3);
  145. GaussianFactor::shared_ptr expLinFactor(
  146. new JacobianFactor(key1, A1, b, model));
  147. EXPECT(assert_equal(*expLinFactor, *actLinFactor, 1e-5));
  148. }
  149. //******************************************************************************
  150. TEST ( NonlinearEquality, allow_error_optimize ) {
  151. Symbol key1('x', 1);
  152. Pose2 feasible1(1.0, 2.0, 3.0);
  153. double error_gain = 500.0;
  154. PoseNLE nle(key1, feasible1, error_gain);
  155. // add to a graph
  156. NonlinearFactorGraph graph;
  157. graph += nle;
  158. // initialize away from the ideal
  159. Pose2 initPose(0.0, 2.0, 3.0);
  160. Values init;
  161. init.insert(key1, initPose);
  162. // optimize
  163. Ordering ordering;
  164. ordering.push_back(key1);
  165. Values result = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
  166. // verify
  167. Values expected;
  168. expected.insert(key1, feasible1);
  169. EXPECT(assert_equal(expected, result));
  170. }
  171. //******************************************************************************
  172. TEST ( NonlinearEquality, allow_error_optimize_with_factors ) {
  173. // create a hard constraint
  174. Symbol key1('x', 1);
  175. Pose2 feasible1(1.0, 2.0, 3.0);
  176. // initialize away from the ideal
  177. Values init;
  178. Pose2 initPose(0.0, 2.0, 3.0);
  179. init.insert(key1, initPose);
  180. double error_gain = 500.0;
  181. PoseNLE nle(key1, feasible1, error_gain);
  182. // create a soft prior that conflicts
  183. PosePrior prior(key1, initPose, noiseModel::Isotropic::Sigma(3, 0.1));
  184. // add to a graph
  185. NonlinearFactorGraph graph;
  186. graph += nle;
  187. graph += prior;
  188. // optimize
  189. Ordering ordering;
  190. ordering.push_back(key1);
  191. Values actual = LevenbergMarquardtOptimizer(graph, init, ordering).optimize();
  192. // verify
  193. Values expected;
  194. expected.insert(key1, feasible1);
  195. EXPECT(assert_equal(expected, actual));
  196. }
  197. //******************************************************************************
  198. static SharedDiagonal hard_model = noiseModel::Constrained::All(2);
  199. static SharedDiagonal soft_model = noiseModel::Isotropic::Sigma(2, 1.0);
  200. //******************************************************************************
  201. TEST( testNonlinearEqualityConstraint, unary_basics ) {
  202. Point2 pt(1.0, 2.0);
  203. Symbol key1('x', 1);
  204. double mu = 1000.0;
  205. eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
  206. Values config1;
  207. config1.insert(key, pt);
  208. EXPECT(constraint.active(config1));
  209. EXPECT(assert_equal(Z_2x1, constraint.evaluateError(pt), tol));
  210. EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
  211. EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
  212. Values config2;
  213. Point2 ptBad1(2.0, 2.0);
  214. config2.insert(key, ptBad1);
  215. EXPECT(constraint.active(config2));
  216. EXPECT(
  217. assert_equal(Vector2(1.0, 0.0), constraint.evaluateError(ptBad1), tol));
  218. EXPECT(
  219. assert_equal(Vector2(1.0, 0.0), constraint.unwhitenedError(config2), tol));
  220. EXPECT_DOUBLES_EQUAL(500.0, constraint.error(config2), tol);
  221. }
  222. //******************************************************************************
  223. TEST( testNonlinearEqualityConstraint, unary_linearization ) {
  224. Point2 pt(1.0, 2.0);
  225. Symbol key1('x', 1);
  226. double mu = 1000.0;
  227. eq2D::UnaryEqualityConstraint constraint(pt, key, mu);
  228. Values config1;
  229. config1.insert(key, pt);
  230. GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
  231. GaussianFactor::shared_ptr expected1(
  232. new JacobianFactor(key, I_2x2, Z_2x1, hard_model));
  233. EXPECT(assert_equal(*expected1, *actual1, tol));
  234. Values config2;
  235. Point2 ptBad(2.0, 2.0);
  236. config2.insert(key, ptBad);
  237. GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
  238. GaussianFactor::shared_ptr expected2(
  239. new JacobianFactor(key, I_2x2, Vector2(-1.0, 0.0), hard_model));
  240. EXPECT(assert_equal(*expected2, *actual2, tol));
  241. }
  242. //******************************************************************************
  243. TEST( testNonlinearEqualityConstraint, unary_simple_optimization ) {
  244. // create a single-node graph with a soft and hard constraint to
  245. // ensure that the hard constraint overrides the soft constraint
  246. Point2 truth_pt(1.0, 2.0);
  247. Symbol key('x', 1);
  248. double mu = 10.0;
  249. eq2D::UnaryEqualityConstraint::shared_ptr constraint(
  250. new eq2D::UnaryEqualityConstraint(truth_pt, key, mu));
  251. Point2 badPt(100.0, -200.0);
  252. simulated2D::Prior::shared_ptr factor(
  253. new simulated2D::Prior(badPt, soft_model, key));
  254. NonlinearFactorGraph graph;
  255. graph.push_back(constraint);
  256. graph.push_back(factor);
  257. Values initValues;
  258. initValues.insert(key, badPt);
  259. // verify error values
  260. EXPECT(constraint->active(initValues));
  261. Values expected;
  262. expected.insert(key, truth_pt);
  263. EXPECT(constraint->active(expected));
  264. EXPECT_DOUBLES_EQUAL(0.0, constraint->error(expected), tol);
  265. Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
  266. EXPECT(assert_equal(expected, actual, tol));
  267. }
  268. //******************************************************************************
  269. TEST( testNonlinearEqualityConstraint, odo_basics ) {
  270. Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
  271. Symbol key1('x', 1), key2('x', 2);
  272. double mu = 1000.0;
  273. eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
  274. Values config1;
  275. config1.insert(key1, x1);
  276. config1.insert(key2, x2);
  277. EXPECT(constraint.active(config1));
  278. EXPECT(assert_equal(Z_2x1, constraint.evaluateError(x1, x2), tol));
  279. EXPECT(assert_equal(Z_2x1, constraint.unwhitenedError(config1), tol));
  280. EXPECT_DOUBLES_EQUAL(0.0, constraint.error(config1), tol);
  281. Values config2;
  282. Point2 x1bad(2.0, 2.0);
  283. Point2 x2bad(2.0, 2.0);
  284. config2.insert(key1, x1bad);
  285. config2.insert(key2, x2bad);
  286. EXPECT(constraint.active(config2));
  287. EXPECT(
  288. assert_equal(Vector2(-1.0, -1.0), constraint.evaluateError(x1bad, x2bad), tol));
  289. EXPECT(
  290. assert_equal(Vector2(-1.0, -1.0), constraint.unwhitenedError(config2), tol));
  291. EXPECT_DOUBLES_EQUAL(1000.0, constraint.error(config2), tol);
  292. }
  293. //******************************************************************************
  294. TEST( testNonlinearEqualityConstraint, odo_linearization ) {
  295. Point2 x1(1.0, 2.0), x2(2.0, 3.0), odom(1.0, 1.0);
  296. Symbol key1('x', 1), key2('x', 2);
  297. double mu = 1000.0;
  298. eq2D::OdoEqualityConstraint constraint(odom, key1, key2, mu);
  299. Values config1;
  300. config1.insert(key1, x1);
  301. config1.insert(key2, x2);
  302. GaussianFactor::shared_ptr actual1 = constraint.linearize(config1);
  303. GaussianFactor::shared_ptr expected1(
  304. new JacobianFactor(key1, -I_2x2, key2, I_2x2, Z_2x1,
  305. hard_model));
  306. EXPECT(assert_equal(*expected1, *actual1, tol));
  307. Values config2;
  308. Point2 x1bad(2.0, 2.0);
  309. Point2 x2bad(2.0, 2.0);
  310. config2.insert(key1, x1bad);
  311. config2.insert(key2, x2bad);
  312. GaussianFactor::shared_ptr actual2 = constraint.linearize(config2);
  313. GaussianFactor::shared_ptr expected2(
  314. new JacobianFactor(key1, -I_2x2, key2, I_2x2, Vector2(1.0, 1.0),
  315. hard_model));
  316. EXPECT(assert_equal(*expected2, *actual2, tol));
  317. }
  318. //******************************************************************************
  319. TEST( testNonlinearEqualityConstraint, odo_simple_optimize ) {
  320. // create a two-node graph, connected by an odometry constraint, with
  321. // a hard prior on one variable, and a conflicting soft prior
  322. // on the other variable - the constraints should override the soft constraint
  323. Point2 truth_pt1(1.0, 2.0), truth_pt2(3.0, 2.0);
  324. Symbol key1('x', 1), key2('x', 2);
  325. // hard prior on x1
  326. eq2D::UnaryEqualityConstraint::shared_ptr constraint1(
  327. new eq2D::UnaryEqualityConstraint(truth_pt1, key1));
  328. // soft prior on x2
  329. Point2 badPt(100.0, -200.0);
  330. simulated2D::Prior::shared_ptr factor(
  331. new simulated2D::Prior(badPt, soft_model, key2));
  332. // odometry constraint
  333. eq2D::OdoEqualityConstraint::shared_ptr constraint2(
  334. new eq2D::OdoEqualityConstraint(truth_pt2-truth_pt1, key1, key2));
  335. NonlinearFactorGraph graph;
  336. graph.push_back(constraint1);
  337. graph.push_back(constraint2);
  338. graph.push_back(factor);
  339. Values initValues;
  340. initValues.insert(key1, Point2(0,0));
  341. initValues.insert(key2, badPt);
  342. Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
  343. Values expected;
  344. expected.insert(key1, truth_pt1);
  345. expected.insert(key2, truth_pt2);
  346. CHECK(assert_equal(expected, actual, tol));
  347. }
  348. //******************************************************************************
  349. TEST (testNonlinearEqualityConstraint, two_pose ) {
  350. /*
  351. * Determining a ground truth linear system
  352. * with two poses seeing one landmark, with each pose
  353. * constrained to a particular value
  354. */
  355. NonlinearFactorGraph graph;
  356. Symbol x1('x', 1), x2('x', 2);
  357. Symbol l1('l', 1), l2('l', 2);
  358. Point2 pt_x1(1.0, 1.0), pt_x2(5.0, 6.0);
  359. graph += eq2D::UnaryEqualityConstraint(pt_x1, x1);
  360. graph += eq2D::UnaryEqualityConstraint(pt_x2, x2);
  361. Point2 z1(0.0, 5.0);
  362. SharedNoiseModel sigma(noiseModel::Isotropic::Sigma(2, 0.1));
  363. graph += simulated2D::Measurement(z1, sigma, x1, l1);
  364. Point2 z2(-4.0, 0.0);
  365. graph += simulated2D::Measurement(z2, sigma, x2, l2);
  366. graph += eq2D::PointEqualityConstraint(l1, l2);
  367. Values initialEstimate;
  368. initialEstimate.insert(x1, pt_x1);
  369. initialEstimate.insert(x2, Point2(0,0));
  370. initialEstimate.insert(l1, Point2(1.0, 6.0)); // ground truth
  371. initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
  372. Values actual =
  373. LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
  374. Values expected;
  375. expected.insert(x1, pt_x1);
  376. expected.insert(l1, Point2(1.0, 6.0));
  377. expected.insert(l2, Point2(1.0, 6.0));
  378. expected.insert(x2, Point2(5.0, 6.0));
  379. CHECK(assert_equal(expected, actual, 1e-5));
  380. }
  381. //******************************************************************************
  382. TEST (testNonlinearEqualityConstraint, map_warp ) {
  383. // get a graph
  384. NonlinearFactorGraph graph;
  385. // keys
  386. Symbol x1('x', 1), x2('x', 2);
  387. Symbol l1('l', 1), l2('l', 2);
  388. // constant constraint on x1
  389. Point2 pose1(1.0, 1.0);
  390. graph += eq2D::UnaryEqualityConstraint(pose1, x1);
  391. SharedDiagonal sigma = noiseModel::Isotropic::Sigma(2, 0.1);
  392. // measurement from x1 to l1
  393. Point2 z1(0.0, 5.0);
  394. graph += simulated2D::Measurement(z1, sigma, x1, l1);
  395. // measurement from x2 to l2
  396. Point2 z2(-4.0, 0.0);
  397. graph += simulated2D::Measurement(z2, sigma, x2, l2);
  398. // equality constraint between l1 and l2
  399. graph += eq2D::PointEqualityConstraint(l1, l2);
  400. // create an initial estimate
  401. Values initialEstimate;
  402. initialEstimate.insert(x1, Point2(1.0, 1.0));
  403. initialEstimate.insert(l1, Point2(1.0, 6.0));
  404. initialEstimate.insert(l2, Point2(-4.0, 0.0)); // starting with a separate reference frame
  405. initialEstimate.insert(x2, Point2(0.0, 0.0)); // other pose starts at origin
  406. // optimize
  407. Values actual =
  408. LevenbergMarquardtOptimizer(graph, initialEstimate).optimize();
  409. Values expected;
  410. expected.insert(x1, Point2(1.0, 1.0));
  411. expected.insert(l1, Point2(1.0, 6.0));
  412. expected.insert(l2, Point2(1.0, 6.0));
  413. expected.insert(x2, Point2(5.0, 6.0));
  414. CHECK(assert_equal(expected, actual, tol));
  415. }
  416. //******************************************************************************
  417. TEST (testNonlinearEqualityConstraint, stereo_constrained ) {
  418. // make a realistic calibration matrix
  419. static double fov = 60; // degrees
  420. static int w = 640, h = 480;
  421. static Cal3_S2 K(fov, w, h);
  422. static boost::shared_ptr<Cal3_S2> shK(new Cal3_S2(K));
  423. // create initial estimates
  424. Rot3 faceTowardsY(Point3(1, 0, 0), Point3(0, 0, -1), Point3(0, 1, 0));
  425. Pose3 poseLeft(faceTowardsY, Point3(0, 0, 0)); // origin, left camera
  426. PinholeCamera<Cal3_S2> leftCamera(poseLeft, K);
  427. Pose3 poseRight(faceTowardsY, Point3(2, 0, 0)); // 2 units to the right
  428. PinholeCamera<Cal3_S2> rightCamera(poseRight, K);
  429. Point3 landmark(1, 5, 0); //centered between the cameras, 5 units away
  430. // keys
  431. Symbol key_x1('x', 1), key_x2('x', 2);
  432. Symbol key_l1('l', 1), key_l2('l', 2);
  433. // create graph
  434. NonlinearFactorGraph graph;
  435. // create equality constraints for poses
  436. graph += NonlinearEquality<Pose3>(key_x1, leftCamera.pose());
  437. graph += NonlinearEquality<Pose3>(key_x2, rightCamera.pose());
  438. // create factors
  439. SharedDiagonal vmodel = noiseModel::Unit::Create(2);
  440. graph += GenericProjectionFactor<Pose3, Point3, Cal3_S2>(
  441. leftCamera.project(landmark), vmodel, key_x1, key_l1, shK);
  442. graph += GenericProjectionFactor<Pose3, Point3, Cal3_S2>(
  443. rightCamera.project(landmark), vmodel, key_x2, key_l2, shK);
  444. // add equality constraint saying there is only one point
  445. graph += NonlinearEquality2<Point3>(key_l1, key_l2);
  446. // create initial data
  447. Point3 landmark1(0.5, 5, 0);
  448. Point3 landmark2(1.5, 5, 0);
  449. Values initValues;
  450. initValues.insert(key_x1, poseLeft);
  451. initValues.insert(key_x2, poseRight);
  452. initValues.insert(key_l1, landmark1);
  453. initValues.insert(key_l2, landmark2);
  454. // optimize
  455. Values actual = LevenbergMarquardtOptimizer(graph, initValues).optimize();
  456. // create config
  457. Values truthValues;
  458. truthValues.insert(key_x1, leftCamera.pose());
  459. truthValues.insert(key_x2, rightCamera.pose());
  460. truthValues.insert(key_l1, landmark);
  461. truthValues.insert(key_l2, landmark);
  462. // check if correct
  463. CHECK(assert_equal(truthValues, actual, 1e-5));
  464. }
  465. //******************************************************************************
  466. int main() {
  467. TestResult tr;
  468. return TestRegistry::runAllTests(tr);
  469. }
  470. //******************************************************************************