testExpressionFactor.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774
  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 testExpressionFactor.cpp
  10. * @date September 18, 2014
  11. * @author Frank Dellaert
  12. * @author Paul Furgale
  13. * @brief unit tests for Block Automatic Differentiation
  14. */
  15. #include <CppUnitLite/TestHarness.h>
  16. #include <gtsam/base/Testable.h>
  17. #include <gtsam/nonlinear/ExpressionFactor.h>
  18. #include <gtsam/nonlinear/NonlinearFactorGraph.h>
  19. #include <gtsam/nonlinear/PriorFactor.h>
  20. #include <gtsam/nonlinear/expressionTesting.h>
  21. #include <gtsam/slam/GeneralSFMFactor.h>
  22. #include <gtsam/slam/ProjectionFactor.h>
  23. #include <gtsam/slam/expressions.h>
  24. #include <boost/assign/list_of.hpp>
  25. using boost::assign::list_of;
  26. using namespace std::placeholders;
  27. using namespace std;
  28. using namespace gtsam;
  29. Point2 measured(-17, 30);
  30. SharedNoiseModel model = noiseModel::Unit::Create(2);
  31. // This deals with the overload problem and makes the expressions factor
  32. // understand that we work on Point3
  33. Point2 (*Project)(const Point3&, OptionalJacobian<2, 3>) = &PinholeBase::Project;
  34. namespace leaf {
  35. // Create some values
  36. struct MyValues: public Values {
  37. MyValues() {
  38. insert(2, Point2(3, 5));
  39. }
  40. } values;
  41. // Create leaf
  42. Point2_ p(2);
  43. }
  44. /* ************************************************************************* */
  45. // Leaf
  46. TEST(ExpressionFactor, Leaf) {
  47. using namespace leaf;
  48. // Create old-style factor to create expected value and derivatives.
  49. PriorFactor<Point2> old(2, Point2(0, 0), model);
  50. // Create the equivalent factor with expression.
  51. ExpressionFactor<Point2> f(model, Point2(0, 0), p);
  52. // Check values and derivatives.
  53. EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9);
  54. EXPECT_LONGS_EQUAL(2, f.dim());
  55. boost::shared_ptr<GaussianFactor> gf2 = f.linearize(values);
  56. EXPECT(assert_equal(*old.linearize(values), *gf2, 1e-9));
  57. }
  58. /* ************************************************************************* */
  59. // Test leaf expression with noise model of different variance.
  60. TEST(ExpressionFactor, Model) {
  61. using namespace leaf;
  62. SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01));
  63. // Create old-style factor to create expected value and derivatives.
  64. PriorFactor<Point2> old(2, Point2(0, 0), model);
  65. // Create the equivalent factor with expression.
  66. ExpressionFactor<Point2> f(model, Point2(0, 0), p);
  67. // Check values and derivatives.
  68. EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9);
  69. EXPECT_LONGS_EQUAL(2, f.dim());
  70. boost::shared_ptr<GaussianFactor> gf2 = f.linearize(values);
  71. EXPECT(assert_equal(*old.linearize(values), *gf2, 1e-9));
  72. EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-5, 1e-5); // another way
  73. }
  74. /* ************************************************************************* */
  75. // Test leaf expression with constrained noise model.
  76. TEST(ExpressionFactor, Constrained) {
  77. using namespace leaf;
  78. SharedDiagonal model = noiseModel::Constrained::MixedSigmas(Vector2(0.2, 0));
  79. // Create old-style factor to create expected value and derivatives
  80. PriorFactor<Point2> old(2, Point2(0, 0), model);
  81. // Concise version
  82. ExpressionFactor<Point2> f(model, Point2(0, 0), p);
  83. EXPECT_DOUBLES_EQUAL(old.error(values), f.error(values), 1e-9);
  84. EXPECT_LONGS_EQUAL(2, f.dim());
  85. boost::shared_ptr<GaussianFactor> gf2 = f.linearize(values);
  86. EXPECT(assert_equal(*old.linearize(values), *gf2, 1e-9));
  87. }
  88. /* ************************************************************************* */
  89. // Unary(Leaf))
  90. TEST(ExpressionFactor, Unary) {
  91. // Create some values
  92. Values values;
  93. values.insert(2, Point3(0, 0, 1));
  94. JacobianFactor expected( //
  95. 2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0).finished(), //
  96. Vector2(-17, 30));
  97. // Create leaves
  98. Point3_ p(2);
  99. // Concise version
  100. ExpressionFactor<Point2> f(model, measured, project(p));
  101. EXPECT_LONGS_EQUAL(2, f.dim());
  102. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  103. boost::shared_ptr<JacobianFactor> jf = //
  104. boost::dynamic_pointer_cast<JacobianFactor>(gf);
  105. EXPECT(assert_equal(expected, *jf, 1e-9));
  106. }
  107. /* ************************************************************************* */
  108. // Unary(Leaf)) and Unary(Unary(Leaf)))
  109. // wide version (not handled in fixed-size pipeline)
  110. typedef Eigen::Matrix<double,9,3> Matrix93;
  111. Vector9 wide(const Point3& p, OptionalJacobian<9,3> H) {
  112. Vector9 v;
  113. v << p, p, p;
  114. if (H) *H << I_3x3, I_3x3, I_3x3;
  115. return v;
  116. }
  117. typedef Eigen::Matrix<double,9,9> Matrix9;
  118. Vector9 id9(const Vector9& v, OptionalJacobian<9,9> H) {
  119. if (H) *H = Matrix9::Identity();
  120. return v;
  121. }
  122. TEST(ExpressionFactor, Wide) {
  123. // Create some values
  124. Values values;
  125. values.insert(2, Point3(0, 0, 1));
  126. Point3_ point(2);
  127. Vector9 measured;
  128. measured.setZero();
  129. Expression<Vector9> expression(wide,point);
  130. SharedNoiseModel model = noiseModel::Unit::Create(9);
  131. ExpressionFactor<Vector9> f1(model, measured, expression);
  132. EXPECT_CORRECT_FACTOR_JACOBIANS(f1, values, 1e-5, 1e-9);
  133. Expression<Vector9> expression2(id9,expression);
  134. ExpressionFactor<Vector9> f2(model, measured, expression2);
  135. EXPECT_CORRECT_FACTOR_JACOBIANS(f2, values, 1e-5, 1e-9);
  136. }
  137. /* ************************************************************************* */
  138. static Point2 myUncal(const Cal3_S2& K, const Point2& p,
  139. OptionalJacobian<2,5> Dcal, OptionalJacobian<2,2> Dp) {
  140. return K.uncalibrate(p, Dcal, Dp);
  141. }
  142. // Binary(Leaf,Leaf)
  143. TEST(ExpressionFactor, Binary) {
  144. typedef internal::BinaryExpression<Point2, Cal3_S2, Point2> Binary;
  145. Cal3_S2_ K_(1);
  146. Point2_ p_(2);
  147. Binary binary(myUncal, K_, p_);
  148. // Create some values
  149. Values values;
  150. values.insert(1, Cal3_S2());
  151. values.insert(2, Point2(0, 0));
  152. // Check size
  153. size_t size = binary.traceSize();
  154. // Use Variable Length Array, allocated on stack by gcc
  155. // Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla
  156. internal::ExecutionTraceStorage traceStorage[size];
  157. internal::ExecutionTrace<Point2> trace;
  158. Point2 value = binary.traceExecution(values, trace, traceStorage);
  159. EXPECT(assert_equal(Point2(0,0),value, 1e-9));
  160. // trace.print();
  161. // Expected Jacobians
  162. Matrix25 expected25;
  163. expected25 << 0, 0, 0, 1, 0, 0, 0, 0, 0, 1;
  164. Matrix2 expected22;
  165. expected22 << 1, 0, 0, 1;
  166. // Check matrices
  167. boost::optional<Binary::Record*> r = trace.record<Binary::Record>();
  168. CHECK(r);
  169. EXPECT(assert_equal(expected25, (Matrix ) (*r)->dTdA1, 1e-9));
  170. EXPECT(assert_equal(expected22, (Matrix ) (*r)->dTdA2, 1e-9));
  171. }
  172. /* ************************************************************************* */
  173. // Unary(Binary(Leaf,Leaf))
  174. TEST(ExpressionFactor, Shallow) {
  175. // Create some values
  176. Values values;
  177. values.insert(1, Pose3());
  178. values.insert(2, Point3(0, 0, 1));
  179. // Create old-style factor to create expected value and derivatives
  180. GenericProjectionFactor<Pose3, Point3> old(measured, model, 1, 2,
  181. boost::make_shared<Cal3_S2>());
  182. double expected_error = old.error(values);
  183. GaussianFactor::shared_ptr expected = old.linearize(values);
  184. // Create leaves
  185. Pose3_ x_(1);
  186. Point3_ p_(2);
  187. // Construct expression, concise evrsion
  188. Point2_ expression = project(transformTo(x_, p_));
  189. // Get and check keys and dims
  190. KeyVector keys;
  191. FastVector<int> dims;
  192. boost::tie(keys, dims) = expression.keysAndDims();
  193. LONGS_EQUAL(2,keys.size());
  194. LONGS_EQUAL(2,dims.size());
  195. LONGS_EQUAL(1,keys[0]);
  196. LONGS_EQUAL(2,keys[1]);
  197. LONGS_EQUAL(6,dims[0]);
  198. LONGS_EQUAL(3,dims[1]);
  199. // traceExecution of shallow tree
  200. typedef internal::UnaryExpression<Point2, Point3> Unary;
  201. size_t size = expression.traceSize();
  202. internal::ExecutionTraceStorage traceStorage[size];
  203. internal::ExecutionTrace<Point2> trace;
  204. Point2 value = expression.traceExecution(values, trace, traceStorage);
  205. EXPECT(assert_equal(Point2(0,0),value, 1e-9));
  206. // trace.print();
  207. // Expected Jacobians
  208. Matrix23 expected23;
  209. expected23 << 1, 0, 0, 0, 1, 0;
  210. // Check matrices
  211. boost::optional<Unary::Record*> r = trace.record<Unary::Record>();
  212. CHECK(r);
  213. EXPECT(assert_equal(expected23, (Matrix)(*r)->dTdA1, 1e-9));
  214. // Linearization
  215. ExpressionFactor<Point2> f2(model, measured, expression);
  216. EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
  217. EXPECT_LONGS_EQUAL(2, f2.dim());
  218. boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
  219. EXPECT(assert_equal(*expected, *gf2, 1e-9));
  220. }
  221. /* ************************************************************************* */
  222. // Binary(Leaf,Unary(Binary(Leaf,Leaf)))
  223. TEST(ExpressionFactor, tree) {
  224. // Create some values
  225. Values values;
  226. values.insert(1, Pose3());
  227. values.insert(2, Point3(0, 0, 1));
  228. values.insert(3, Cal3_S2());
  229. // Create old-style factor to create expected value and derivatives
  230. GeneralSFMFactor2<Cal3_S2> old(measured, model, 1, 2, 3);
  231. double expected_error = old.error(values);
  232. GaussianFactor::shared_ptr expected = old.linearize(values);
  233. // Create leaves
  234. Pose3_ x(1);
  235. Point3_ p(2);
  236. Cal3_S2_ K(3);
  237. // Create expression tree
  238. Point3_ p_cam(x, &Pose3::transformTo, p);
  239. Point2_ xy_hat(Project, p_cam);
  240. Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat);
  241. // Create factor and check value, dimension, linearization
  242. ExpressionFactor<Point2> f(model, measured, uv_hat);
  243. EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9);
  244. EXPECT_LONGS_EQUAL(2, f.dim());
  245. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  246. EXPECT(assert_equal(*expected, *gf, 1e-9));
  247. // Concise version
  248. ExpressionFactor<Point2> f2(model, measured,
  249. uncalibrate(K, project(transformTo(x, p))));
  250. EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
  251. EXPECT_LONGS_EQUAL(2, f2.dim());
  252. boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
  253. EXPECT(assert_equal(*expected, *gf2, 1e-9));
  254. // Try ternary version
  255. ExpressionFactor<Point2> f3(model, measured, project3(x, p, K));
  256. EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9);
  257. EXPECT_LONGS_EQUAL(2, f3.dim());
  258. boost::shared_ptr<GaussianFactor> gf3 = f3.linearize(values);
  259. EXPECT(assert_equal(*expected, *gf3, 1e-9));
  260. }
  261. /* ************************************************************************* */
  262. TEST(ExpressionFactor, Compose1) {
  263. // Create expression
  264. Rot3_ R1(1), R2(2);
  265. Rot3_ R3 = R1 * R2;
  266. // Create factor
  267. ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
  268. // Create some values
  269. Values values;
  270. values.insert(1, Rot3());
  271. values.insert(2, Rot3());
  272. // Check unwhitenedError
  273. std::vector<Matrix> H(2);
  274. Vector actual = f.unwhitenedError(values, H);
  275. EXPECT(assert_equal(I_3x3, H[0],1e-9));
  276. EXPECT(assert_equal(I_3x3, H[1],1e-9));
  277. // Check linearization
  278. JacobianFactor expected(1, I_3x3, 2, I_3x3, Z_3x1);
  279. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  280. boost::shared_ptr<JacobianFactor> jf = //
  281. boost::dynamic_pointer_cast<JacobianFactor>(gf);
  282. EXPECT(assert_equal(expected, *jf,1e-9));
  283. }
  284. /* ************************************************************************* */
  285. // Test compose with arguments referring to the same rotation
  286. TEST(ExpressionFactor, compose2) {
  287. // Create expression
  288. Rot3_ R1(1), R2(1);
  289. Rot3_ R3 = R1 * R2;
  290. // Create factor
  291. ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
  292. // Create some values
  293. Values values;
  294. values.insert(1, Rot3());
  295. // Check unwhitenedError
  296. std::vector<Matrix> H(1);
  297. Vector actual = f.unwhitenedError(values, H);
  298. EXPECT_LONGS_EQUAL(1, H.size());
  299. EXPECT(assert_equal(2*I_3x3, H[0],1e-9));
  300. // Check linearization
  301. JacobianFactor expected(1, 2 * I_3x3, Z_3x1);
  302. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  303. boost::shared_ptr<JacobianFactor> jf = //
  304. boost::dynamic_pointer_cast<JacobianFactor>(gf);
  305. EXPECT(assert_equal(expected, *jf,1e-9));
  306. }
  307. /* ************************************************************************* */
  308. // Test compose with one arguments referring to a constant same rotation
  309. TEST(ExpressionFactor, compose3) {
  310. // Create expression
  311. Rot3_ R1(Rot3::identity()), R2(3);
  312. Rot3_ R3 = R1 * R2;
  313. // Create factor
  314. ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
  315. // Create some values
  316. Values values;
  317. values.insert(3, Rot3());
  318. // Check unwhitenedError
  319. std::vector<Matrix> H(1);
  320. Vector actual = f.unwhitenedError(values, H);
  321. EXPECT_LONGS_EQUAL(1, H.size());
  322. EXPECT(assert_equal(I_3x3, H[0],1e-9));
  323. // Check linearization
  324. JacobianFactor expected(3, I_3x3, Z_3x1);
  325. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  326. boost::shared_ptr<JacobianFactor> jf = //
  327. boost::dynamic_pointer_cast<JacobianFactor>(gf);
  328. EXPECT(assert_equal(expected, *jf,1e-9));
  329. }
  330. /* ************************************************************************* */
  331. // Test compose with three arguments
  332. Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3,
  333. OptionalJacobian<3, 3> H1, OptionalJacobian<3, 3> H2, OptionalJacobian<3, 3> H3) {
  334. // return dummy derivatives (not correct, but that's ok for testing here)
  335. if (H1)
  336. *H1 = I_3x3;
  337. if (H2)
  338. *H2 = I_3x3;
  339. if (H3)
  340. *H3 = I_3x3;
  341. return R1 * (R2 * R3);
  342. }
  343. TEST(ExpressionFactor, composeTernary) {
  344. // Create expression
  345. Rot3_ A(1), B(2), C(3);
  346. Rot3_ ABC(composeThree, A, B, C);
  347. // Create factor
  348. ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), ABC);
  349. // Create some values
  350. Values values;
  351. values.insert(1, Rot3());
  352. values.insert(2, Rot3());
  353. values.insert(3, Rot3());
  354. // Check unwhitenedError
  355. std::vector<Matrix> H(3);
  356. Vector actual = f.unwhitenedError(values, H);
  357. EXPECT_LONGS_EQUAL(3, H.size());
  358. EXPECT(assert_equal(I_3x3, H[0],1e-9));
  359. EXPECT(assert_equal(I_3x3, H[1],1e-9));
  360. EXPECT(assert_equal(I_3x3, H[2],1e-9));
  361. // Check linearization
  362. JacobianFactor expected(1, I_3x3, 2, I_3x3, 3, I_3x3, Z_3x1);
  363. boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
  364. boost::shared_ptr<JacobianFactor> jf = //
  365. boost::dynamic_pointer_cast<JacobianFactor>(gf);
  366. EXPECT(assert_equal(expected, *jf,1e-9));
  367. }
  368. TEST(ExpressionFactor, tree_finite_differences) {
  369. // Create some values
  370. Values values;
  371. values.insert(1, Pose3());
  372. values.insert(2, Point3(0, 0, 1));
  373. values.insert(3, Cal3_S2());
  374. // Create leaves
  375. Pose3_ x(1);
  376. Point3_ p(2);
  377. Cal3_S2_ K(3);
  378. // Create expression tree
  379. Point3_ p_cam(x, &Pose3::transformTo, p);
  380. Point2_ xy_hat(Project, p_cam);
  381. Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat);
  382. const double fd_step = 1e-5;
  383. const double tolerance = 1e-5;
  384. EXPECT_CORRECT_EXPRESSION_JACOBIANS(uv_hat, values, fd_step, tolerance);
  385. }
  386. TEST(ExpressionFactor, push_back) {
  387. NonlinearFactorGraph graph;
  388. graph.addExpressionFactor(model, Point2(0, 0), leaf::p);
  389. }
  390. /* ************************************************************************* */
  391. // Test with multiple compositions on duplicate keys
  392. struct Combine {
  393. double a, b;
  394. Combine(double a, double b) : a(a), b(b) {}
  395. double operator()(const double& x, const double& y, OptionalJacobian<1, 1> H1,
  396. OptionalJacobian<1, 1> H2) {
  397. if (H1) (*H1) << a;
  398. if (H2) (*H2) << b;
  399. return a * x + b * y;
  400. }
  401. };
  402. TEST(Expression, testMultipleCompositions) {
  403. const double tolerance = 1e-5;
  404. const double fd_step = 1e-5;
  405. Values values;
  406. values.insert(1, 10.0);
  407. values.insert(2, 20.0);
  408. Expression<double> v1_(Key(1));
  409. Expression<double> v2_(Key(2));
  410. // BinaryExpression(1,2)
  411. // Leaf, key = 1
  412. // Leaf, key = 2
  413. Expression<double> sum1_(Combine(1, 2), v1_, v2_);
  414. EXPECT(sum1_.keys() == list_of(1)(2));
  415. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum1_, values, fd_step, tolerance);
  416. // BinaryExpression(3,4)
  417. // BinaryExpression(1,2)
  418. // Leaf, key = 1
  419. // Leaf, key = 2
  420. // Leaf, key = 1
  421. Expression<double> sum2_(Combine(3, 4), sum1_, v1_);
  422. EXPECT(sum2_.keys() == list_of(1)(2));
  423. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum2_, values, fd_step, tolerance);
  424. // BinaryExpression(5,6)
  425. // BinaryExpression(3,4)
  426. // BinaryExpression(1,2)
  427. // Leaf, key = 1
  428. // Leaf, key = 2
  429. // Leaf, key = 1
  430. // BinaryExpression(1,2)
  431. // Leaf, key = 1
  432. // Leaf, key = 2
  433. Expression<double> sum3_(Combine(5, 6), sum1_, sum2_);
  434. EXPECT(sum3_.keys() == list_of(1)(2));
  435. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum3_, values, fd_step, tolerance);
  436. }
  437. /* ************************************************************************* */
  438. // Another test, with Ternary Expressions
  439. static double combine3(const double& x, const double& y, const double& z,
  440. OptionalJacobian<1, 1> H1, OptionalJacobian<1, 1> H2,
  441. OptionalJacobian<1, 1> H3) {
  442. if (H1) (*H1) << 1.0;
  443. if (H2) (*H2) << 2.0;
  444. if (H3) (*H3) << 3.0;
  445. return x + 2.0 * y + 3.0 * z;
  446. }
  447. TEST(Expression, testMultipleCompositions2) {
  448. const double tolerance = 1e-5;
  449. const double fd_step = 1e-5;
  450. Values values;
  451. values.insert(1, 10.0);
  452. values.insert(2, 20.0);
  453. values.insert(3, 30.0);
  454. Expression<double> v1_(Key(1));
  455. Expression<double> v2_(Key(2));
  456. Expression<double> v3_(Key(3));
  457. Expression<double> sum1_(Combine(4,5), v1_, v2_);
  458. EXPECT(sum1_.keys() == list_of(1)(2));
  459. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum1_, values, fd_step, tolerance);
  460. Expression<double> sum2_(combine3, v1_, v2_, v3_);
  461. EXPECT(sum2_.keys() == list_of(1)(2)(3));
  462. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum2_, values, fd_step, tolerance);
  463. Expression<double> sum3_(combine3, v3_, v2_, v1_);
  464. EXPECT(sum3_.keys() == list_of(1)(2)(3));
  465. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum3_, values, fd_step, tolerance);
  466. Expression<double> sum4_(combine3, sum1_, sum2_, sum3_);
  467. EXPECT(sum4_.keys() == list_of(1)(2)(3));
  468. EXPECT_CORRECT_EXPRESSION_JACOBIANS(sum4_, values, fd_step, tolerance);
  469. }
  470. /* ************************************************************************* */
  471. // Test multiplication with the inverse of a matrix
  472. TEST(ExpressionFactor, MultiplyWithInverse) {
  473. auto model = noiseModel::Isotropic::Sigma(3, 1);
  474. // Create expression
  475. Vector3_ f_expr(MultiplyWithInverse<3>(), Expression<Matrix3>(0), Vector3_(1));
  476. // Check derivatives
  477. Values values;
  478. Matrix3 A = Vector3(1, 2, 3).asDiagonal();
  479. A(0, 1) = 0.1;
  480. A(0, 2) = 0.1;
  481. const Vector3 b(0.1, 0.2, 0.3);
  482. values.insert<Matrix3>(0, A);
  483. values.insert<Vector3>(1, b);
  484. ExpressionFactor<Vector3> factor(model, Vector3::Zero(), f_expr);
  485. EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5);
  486. }
  487. /* ************************************************************************* */
  488. // Test multiplication with the inverse of a matrix function
  489. namespace test_operator {
  490. Vector3 f(const Point2& a, const Vector3& b, OptionalJacobian<3, 2> H1,
  491. OptionalJacobian<3, 3> H2) {
  492. Matrix3 A = Vector3(1, 2, 3).asDiagonal();
  493. A(0, 1) = a.x();
  494. A(0, 2) = a.y();
  495. A(1, 0) = a.x();
  496. if (H1) *H1 << b.y(), b.z(), b.x(), 0, 0, 0;
  497. if (H2) *H2 = A;
  498. return A * b;
  499. }
  500. }
  501. TEST(ExpressionFactor, MultiplyWithInverseFunction) {
  502. auto model = noiseModel::Isotropic::Sigma(3, 1);
  503. using test_operator::f;
  504. Vector3_ f_expr(MultiplyWithInverseFunction<Point2, 3>(f),
  505. Expression<Point2>(0), Vector3_(1));
  506. // Check derivatives
  507. Point2 a(1, 2);
  508. const Vector3 b(0.1, 0.2, 0.3);
  509. Matrix32 H1;
  510. Matrix3 A;
  511. const Vector Ab = f(a, b, H1, A);
  512. CHECK(assert_equal(A * b, Ab));
  513. CHECK(assert_equal(
  514. numericalDerivative11<Vector3, Point2>(
  515. std::bind(f, std::placeholders::_1, b, boost::none, boost::none), a),
  516. H1));
  517. Values values;
  518. values.insert<Point2>(0, a);
  519. values.insert<Vector3>(1, b);
  520. ExpressionFactor<Vector3> factor(model, Vector3::Zero(), f_expr);
  521. EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5);
  522. }
  523. /* ************************************************************************* */
  524. // Test N-ary variadic template
  525. class TestNaryFactor
  526. : public gtsam::ExpressionFactorN<gtsam::Point3 /*return type*/,
  527. gtsam::Rot3, gtsam::Point3,
  528. gtsam::Rot3, gtsam::Point3> {
  529. private:
  530. using This = TestNaryFactor;
  531. using Base =
  532. gtsam::ExpressionFactorN<gtsam::Point3 /*return type*/,
  533. gtsam::Rot3, gtsam::Point3, gtsam::Rot3, gtsam::Point3>;
  534. public:
  535. /// default constructor
  536. TestNaryFactor() = default;
  537. ~TestNaryFactor() override = default;
  538. TestNaryFactor(gtsam::Key kR1, gtsam::Key kV1, gtsam::Key kR2, gtsam::Key kV2,
  539. const gtsam::SharedNoiseModel &model, const gtsam::Point3& measured)
  540. : Base({kR1, kV1, kR2, kV2}, model, measured) {
  541. this->initialize(expression({kR1, kV1, kR2, kV2}));
  542. }
  543. /// @return a deep copy of this factor
  544. gtsam::NonlinearFactor::shared_ptr clone() const override {
  545. return boost::static_pointer_cast<gtsam::NonlinearFactor>(
  546. gtsam::NonlinearFactor::shared_ptr(new This(*this)));
  547. }
  548. // Return measurement expression
  549. gtsam::Expression<gtsam::Point3> expression(
  550. const std::array<gtsam::Key, NARY_EXPRESSION_SIZE> &keys) const override {
  551. gtsam::Expression<gtsam::Rot3> R1_(keys[0]);
  552. gtsam::Expression<gtsam::Point3> V1_(keys[1]);
  553. gtsam::Expression<gtsam::Rot3> R2_(keys[2]);
  554. gtsam::Expression<gtsam::Point3> V2_(keys[3]);
  555. return {gtsam::rotate(R1_, V1_) - gtsam::rotate(R2_, V2_)};
  556. }
  557. /** print */
  558. void print(const std::string &s,
  559. const gtsam::KeyFormatter &keyFormatter =
  560. gtsam::DefaultKeyFormatter) const override {
  561. std::cout << s << "TestNaryFactor("
  562. << keyFormatter(Factor::keys_[0]) << ","
  563. << keyFormatter(Factor::keys_[1]) << ","
  564. << keyFormatter(Factor::keys_[2]) << ","
  565. << keyFormatter(Factor::keys_[3]) << ")\n";
  566. gtsam::traits<gtsam::Point3>::Print(measured_, " measured: ");
  567. this->noiseModel_->print(" noise model: ");
  568. }
  569. /** equals */
  570. bool equals(const gtsam::NonlinearFactor &expected,
  571. double tol = 1e-9) const override {
  572. const This *e = dynamic_cast<const This *>(&expected);
  573. return e != nullptr && Base::equals(*e, tol) &&
  574. gtsam::traits<gtsam::Point3>::Equals(measured_,e->measured_, tol);
  575. }
  576. private:
  577. /** Serialization function */
  578. friend class boost::serialization::access;
  579. template <class ARCHIVE>
  580. void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
  581. ar &boost::serialization::make_nvp(
  582. "TestNaryFactor",
  583. boost::serialization::base_object<Base>(*this));
  584. ar &BOOST_SERIALIZATION_NVP(measured_);
  585. }
  586. };
  587. TEST(ExpressionFactor, variadicTemplate) {
  588. using gtsam::symbol_shorthand::R;
  589. using gtsam::symbol_shorthand::V;
  590. // Create factor
  591. TestNaryFactor f(R(0),V(0), R(1), V(1), noiseModel::Unit::Create(3), Point3(0,0,0));
  592. // Create some values
  593. Values values;
  594. values.insert(R(0), Rot3::Ypr(0.1, 0.2, 0.3));
  595. values.insert(V(0), Point3(1, 2, 3));
  596. values.insert(R(1), Rot3::Ypr(0.2, 0.5, 0.2));
  597. values.insert(V(1), Point3(5, 6, 7));
  598. // Check unwhitenedError
  599. std::vector<Matrix> H(4);
  600. Vector actual = f.unwhitenedError(values, H);
  601. EXPECT_LONGS_EQUAL(4, H.size());
  602. EXPECT(assert_equal(Eigen::Vector3d(-5.63578115, -4.85353243, -1.4801204), actual, 1e-5));
  603. EXPECT_CORRECT_FACTOR_JACOBIANS(f, values, 1e-8, 1e-5);
  604. }
  605. TEST(ExpressionFactor, crossProduct) {
  606. auto model = noiseModel::Isotropic::Sigma(3, 1);
  607. // Create expression
  608. const auto a = Vector3_(1);
  609. const auto b = Vector3_(2);
  610. Vector3_ f_expr = cross(a, b);
  611. // Check derivatives
  612. Values values;
  613. values.insert(1, Vector3(0.1, 0.2, 0.3));
  614. values.insert(2, Vector3(0.4, 0.5, 0.6));
  615. ExpressionFactor<Vector3> factor(model, Vector3::Zero(), f_expr);
  616. EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5);
  617. }
  618. TEST(ExpressionFactor, dotProduct) {
  619. auto model = noiseModel::Isotropic::Sigma(1, 1);
  620. // Create expression
  621. const auto a = Vector3_(1);
  622. const auto b = Vector3_(2);
  623. Double_ f_expr = dot(a, b);
  624. // Check derivatives
  625. Values values;
  626. values.insert(1, Vector3(0.1, 0.2, 0.3));
  627. values.insert(2, Vector3(0.4, 0.5, 0.6));
  628. ExpressionFactor<double> factor(model, .0, f_expr);
  629. EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-5);
  630. }
  631. /* ************************************************************************* */
  632. int main() {
  633. TestResult tr;
  634. return TestRegistry::runAllTests(tr);
  635. }
  636. /* ************************************************************************* */