testNavState.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <gtsam/base/lieProxies.h>
24 #include <gtsam/base/testLie.h>
25 
27 
28 using namespace std::placeholders;
29 using namespace std;
30 using namespace gtsam;
31 
34 
35 static const Rot3 kAttitude = Rot3::RzRyRx(0.1, 0.2, 0.3);
36 static const Point3 kPosition(1.0, 2.0, 3.0);
37 static const Pose3 kPose(kAttitude, kPosition);
38 static const Velocity3 kVelocity(0.4, 0.5, 0.6);
39 static const NavState kIdentity;
41 static const Vector3 kOmegaCoriolis(0.02, 0.03, 0.04);
42 static const Vector3 kGravity(0, 0, 9.81);
43 static const Vector9 kZeroXi = Vector9::Zero();
44 
45 static const Point3 V(3, 0.4, -2.2);
46 static const Point3 P(0.2, 0.7, -2);
47 static const Rot3 R = Rot3::Rodrigues(0.3, 0, 0);
48 static const Point3 V2(-6.5, 3.5, 6.2);
49 static const Point3 P2(3.5, -8.2, 4.2);
50 static const NavState T(R, P2, V2);
51 static const NavState T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2, V2);
52 static const NavState T3(Rot3::Rodrigues(-90, 0, 0), Point3(5, 6, 7),
53  Point3(1, 2, 3));
54 
55 //******************************************************************************
56 TEST(NavState, Concept) {
58  GTSAM_CONCEPT_ASSERT(IsManifold<NavState >);
60 }
61 
62 /* ************************************************************************* */
63 TEST(NavState, Constructor) {
64  std::function<NavState(const Rot3&, const Point3&, const Vector3&)> create =
65  std::bind(&NavState::Create, std::placeholders::_1, std::placeholders::_2,
66  std::placeholders::_3, nullptr, nullptr, nullptr);
67  Matrix aH1, aH2, aH3;
68  EXPECT(
70  NavState::Create(kAttitude, kPosition, kVelocity, aH1, aH2, aH3)));
71  EXPECT(
74  EXPECT(
77  EXPECT(
80 }
81 
82 /* ************************************************************************* */
83 TEST(NavState, Constructor2) {
84  std::function<NavState(const Pose3&, const Vector3&)> construct =
85  std::bind(&NavState::FromPoseVelocity, std::placeholders::_1,
86  std::placeholders::_2, nullptr, nullptr);
87  Matrix aH1, aH2;
88  EXPECT(
90  NavState::FromPoseVelocity(kPose, kVelocity, aH1, aH2)));
93 }
94 
95 /* ************************************************************************* */
96 TEST( NavState, Attitude) {
97  Matrix39 aH, eH;
98  Rot3 actual = kState1.attitude(aH);
99  EXPECT(assert_equal(actual, kAttitude));
100  eH = numericalDerivative11<Rot3, NavState>(
101  std::bind(&NavState::attitude, std::placeholders::_1, nullptr), kState1);
102  EXPECT(assert_equal((Matrix )eH, aH));
103 }
104 
105 /* ************************************************************************* */
106 TEST( NavState, Position) {
107  Matrix39 aH, eH;
108  Point3 actual = kState1.position(aH);
109  EXPECT(assert_equal(actual, kPosition));
110  eH = numericalDerivative11<Point3, NavState>(
111  std::bind(&NavState::position, std::placeholders::_1, nullptr),
112  kState1);
113  EXPECT(assert_equal((Matrix )eH, aH));
114 }
115 
116 /* ************************************************************************* */
117 TEST( NavState, Velocity) {
118  Matrix39 aH, eH;
119  Velocity3 actual = kState1.velocity(aH);
120  EXPECT(assert_equal(actual, kVelocity));
121  eH = numericalDerivative11<Velocity3, NavState>(
122  std::bind(&NavState::velocity, std::placeholders::_1, nullptr),
123  kState1);
124  EXPECT(assert_equal((Matrix )eH, aH));
125 }
126 
127 /* ************************************************************************* */
128 TEST( NavState, BodyVelocity) {
129  Matrix39 aH, eH;
130  Velocity3 actual = kState1.bodyVelocity(aH);
131  EXPECT(assert_equal<Velocity3>(actual, kAttitude.unrotate(kVelocity)));
132  eH = numericalDerivative11<Velocity3, NavState>(
133  std::bind(&NavState::bodyVelocity, std::placeholders::_1, nullptr),
134  kState1);
135  EXPECT(assert_equal((Matrix )eH, aH));
136 }
137 
138 /* ************************************************************************* */
139 TEST( NavState, Manifold ) {
140  // Check zero xi
145 
146  // Check definition of retract as operating on components separately
147  Vector9 xi;
148  xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3;
149  Rot3 drot = Rot3::Expmap(xi.head<3>());
150  Point3 dt = Point3(xi.segment<3>(3));
151  Velocity3 dvel = Velocity3(-0.1, -0.2, -0.3);
154  kState1.velocity() + kState1.attitude() * dvel);
157 
158  // roundtrip from state2 to state3 and back
159  NavState state3 = state2.retract(xi);
161 
162  // Check retract derivatives
163  Matrix9 aH1, aH2;
164  kState1.retract(xi, aH1, aH2);
165  std::function<NavState(const NavState&, const Vector9&)> retract =
166  std::bind(&NavState::retract, std::placeholders::_1,
167  std::placeholders::_2, nullptr, nullptr);
170 
171  // Check retract derivatives on state 2
172  const Vector9 xi2 = -3.0*xi;
173  state2.retract(xi2, aH1, aH2);
176 
177  // Check localCoordinates derivatives
178  std::function<Vector9(const NavState&, const NavState&)> local =
179  std::bind(&NavState::localCoordinates, std::placeholders::_1,
180  std::placeholders::_2, nullptr, nullptr);
181  // from state1 to state2
182  kState1.localCoordinates(state2, aH1, aH2);
185  // from identity to state2
186  kIdentity.localCoordinates(state2, aH1, aH2);
189  // from state2 to identity
190  state2.localCoordinates(kIdentity, aH1, aH2);
193 }
194 
195 /* ************************************************************************* */
196 TEST(NavState, Equals) {
197  NavState T3(Rot3::Rodrigues(-90, 0, 0), Point3(5, 6, 7), Point3(1, 2, 3));
198  NavState pose2 = T3;
199  EXPECT(T3.equals(pose2));
201  EXPECT(!T3.equals(origin));
202 }
203 
204 /* ************************************************************************* */
205 TEST(NavState, Compose) {
206  NavState nav_state_a(Rot3::Identity(), {0.0, 1.0, 2.0}, {1.0, -1.0, 1.0});
207  NavState nav_state_b(Rot3::Rx(M_PI_4), {0.0, 1.0, 3.0}, {1.0, -1.0, 2.0});
208  NavState nav_state_c(Rot3::Ry(M_PI / 180.0), {1.0, 1.0, 2.0},
209  {3.0, -1.0, 1.0});
210 
211  auto ab_c = (nav_state_a * nav_state_b) * nav_state_c;
212  auto a_bc = nav_state_a * (nav_state_b * nav_state_c);
213  CHECK(assert_equal(ab_c, a_bc));
214 
215  Matrix actual = (T2 * T2).matrix();
216 
217  Matrix expected = T2.matrix() * T2.matrix();
218  EXPECT(assert_equal(actual, expected, 1e-8));
219 
220  Matrix actualDcompose1, actualDcompose2;
221  T2.compose(T2, actualDcompose1, actualDcompose2);
222 
223  Matrix numericalH1 =
224  numericalDerivative21(testing::compose<NavState>, T2, T2);
225 
226  EXPECT(assert_equal(numericalH1, actualDcompose1, 5e-3));
227  EXPECT(assert_equal(T2.inverse().AdjointMap(), actualDcompose1, 5e-3));
228 
229  Matrix numericalH2 =
230  numericalDerivative22(testing::compose<NavState>, T2, T2);
231  EXPECT(assert_equal(numericalH2, actualDcompose2, 1e-4));
232 }
233 
234 /* ************************************************************************* */
235 // Check compose and its push-forward, another case
236 TEST(NavState, Compose2) {
237  const NavState& T1 = T;
238  Matrix actual = (T1 * T2).matrix();
239  Matrix expected = T1.matrix() * T2.matrix();
240  EXPECT(assert_equal(actual, expected, 1e-8));
241 
242  Matrix actualDcompose1, actualDcompose2;
243  T1.compose(T2, actualDcompose1, actualDcompose2);
244 
245  Matrix numericalH1 =
246  numericalDerivative21(testing::compose<NavState>, T1, T2);
247  EXPECT(assert_equal(numericalH1, actualDcompose1, 5e-3));
248  EXPECT(assert_equal(T2.inverse().AdjointMap(), actualDcompose1, 5e-3));
249 
250  Matrix numericalH2 =
251  numericalDerivative22(testing::compose<NavState>, T1, T2);
252  EXPECT(assert_equal(numericalH2, actualDcompose2, 1e-5));
253 }
254 
255 /* ************************************************************************* */
257  NavState nav_state_a(Rot3::Identity(), {0.0, 1.0, 2.0}, {1.0, -1.0, 1.0});
258  NavState nav_state_b(Rot3::Rx(M_PI_4), {0.0, 1.0, 3.0}, {1.0, -1.0, 2.0});
259  NavState nav_state_c(Rot3::Ry(M_PI / 180.0), {1.0, 1.0, 2.0},
260  {3.0, -1.0, 1.0});
261 
262  auto a_inv = nav_state_a.inverse();
263  auto a_a_inv = nav_state_a * a_inv;
264  CHECK(assert_equal(a_a_inv, NavState()));
265 
266  auto b_inv = nav_state_b.inverse();
267  auto b_b_inv = nav_state_b * b_inv;
268  CHECK(assert_equal(b_b_inv, NavState()));
269 
270  Matrix actualDinverse;
271  Matrix actual = T.inverse(actualDinverse).matrix();
272  Matrix expected = T.matrix().inverse();
273  EXPECT(assert_equal(actual, expected, 1e-8));
274 
275  Matrix numericalH = numericalDerivative11(testing::inverse<NavState>, T);
276  EXPECT(assert_equal(numericalH, actualDinverse, 5e-3));
277  EXPECT(assert_equal(-T.AdjointMap(), actualDinverse, 5e-3));
278 }
279 
280 /* ************************************************************************* */
281 TEST(NavState, InverseDerivatives) {
282  Rot3 R = Rot3::Rodrigues(0.3, 0.4, -0.5);
283  Vector3 v(3.5, -8.2, 4.2);
284  Point3 p(3.5, -8.2, 4.2);
285  NavState T(R, p, v);
286 
287  Matrix numericalH = numericalDerivative11(testing::inverse<NavState>, T);
288  Matrix actualDinverse;
289  T.inverse(actualDinverse);
290  EXPECT(assert_equal(numericalH, actualDinverse, 5e-3));
291  EXPECT(assert_equal(-T.AdjointMap(), actualDinverse, 5e-3));
292 }
293 
294 /* ************************************************************************* */
295 TEST(NavState, Compose_Inverse) {
296  NavState actual = T * T.inverse();
298  EXPECT(assert_equal(actual, expected, 1e-8));
299 }
300 
301 /* ************************************************************************* */
303  NavState s1, s2(Rot3(), Point3(1, 2, 3), Velocity3(0, 0, 0));
304 
305  NavState actual = s1.compose(s2);
306  EXPECT(assert_equal(s2, actual));
307 
308  NavState between = s2.between(s1);
309  NavState expected_between(Rot3(), Point3(-1, -2, -3), Velocity3(0, 0, 0));
310  EXPECT(assert_equal(expected_between, between));
311 
312  NavState expected = T2.inverse() * T3;
313  Matrix actualDBetween1, actualDBetween2;
314  actual = T2.between(T3, actualDBetween1, actualDBetween2);
315  EXPECT(assert_equal(expected, actual));
316 
317  Matrix numericalH1 =
318  numericalDerivative21(testing::between<NavState>, T2, T3);
319  EXPECT(assert_equal(numericalH1, actualDBetween1, 5e-3));
320 
321  Matrix numericalH2 =
322  numericalDerivative22(testing::between<NavState>, T2, T3);
323  EXPECT(assert_equal(numericalH2, actualDBetween2, 1e-5));
324 }
325 
326 /* ************************************************************************* */
330 }
331 
332 /* ************************************************************************* */
333 static const double dt = 2.0;
334 std::function<Vector9(const NavState&, const bool&)> coriolis =
335  std::bind(&NavState::coriolis, std::placeholders::_1, dt, kOmegaCoriolis,
336  std::placeholders::_2, nullptr);
337 
338 TEST(NavState, Coriolis) {
339  Matrix9 aH;
340 
341  // first-order
342  kState1.coriolis(dt, kOmegaCoriolis, false, aH);
344  // second-order
345  kState1.coriolis(dt, kOmegaCoriolis, true, aH);
347 }
348 
349 TEST(NavState, Coriolis2) {
350  Matrix9 aH;
351  NavState state2(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0),
352  Point3(5.0, 1.0, -50.0), Vector3(0.5, 0.0, 0.0));
353 
354  // first-order
355  state2.coriolis(dt, kOmegaCoriolis, false, aH);
357  // second-order
358  state2.coriolis(dt, kOmegaCoriolis, true, aH);
360 }
361 
362 TEST(NavState, Coriolis3) {
370  // Get true first and second order coriolis accelerations
371  double dt = 2.0, dt2 = dt * dt;
372  Vector3 n_omega(0.0, 0.0, 1.0), n_t(1.0, 0.0, 0.0), n_v(0.0, 1.0, 0.0);
373  Vector3 n_aCorr1 = -2.0 * n_omega.cross(n_v),
374  n_aCorr2 = -n_omega.cross(n_omega.cross(n_t));
375  Rot3 nRb = Rot3(-1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 1.0, 0.0),
376  bRn = nRb.inverse();
377 
378  // Get expected first and second order corrections in the nav frame
379  Vector3 n_dP1e = 0.5 * dt2 * n_aCorr1,
380  n_dP2e = 0.5 * dt2 * (n_aCorr1 + n_aCorr2),
381  n_dV1e = dt * n_aCorr1,
382  n_dV2e = dt * (n_aCorr1 + n_aCorr2);
383 
384  // Get expected first and second order corrections in the body frame
385  Vector3 dRe = -dt * (bRn * n_omega),
386  b_dP1e = bRn * n_dP1e, b_dP2e = bRn * n_dP2e,
387  b_dV1e = bRn * n_dV1e, b_dV2e = bRn * n_dV2e;
388 
389  // Get actual first and scond order corrections in body frame
390  NavState kState2(nRb, n_t, n_v);
391  Vector9 dXi1a = kState2.coriolis(dt, n_omega, false),
392  dXi2a = kState2.coriolis(dt, n_omega, true);
393  Vector3 dRa = NavState::dR(dXi1a),
394  b_dP1a = NavState::dP(dXi1a), b_dV1a = NavState::dV(dXi1a),
395  b_dP2a = NavState::dP(dXi2a), b_dV2a = NavState::dV(dXi2a);
396 
397  EXPECT(assert_equal(dRe, dRa));
398  EXPECT(assert_equal(b_dP1e, b_dP1a));
399  EXPECT(assert_equal(b_dV1e, b_dV1a));
400  EXPECT(assert_equal(b_dP2e, b_dP2a));
401  EXPECT(assert_equal(b_dV2e, b_dV2a));
402 
403 }
404 
405 /* ************************************************************************* */
406 TEST(NavState, CorrectPIM) {
407  Vector9 xi;
408  xi << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4, -0.1, -0.2, -0.3;
409  double dt = 0.5;
410  Matrix9 aH1, aH2;
411  std::function<Vector9(const NavState&, const Vector9&)> correctPIM =
412  std::bind(&NavState::correctPIM, std::placeholders::_1,
413  std::placeholders::_2, dt, kGravity, kOmegaCoriolis, false,
414  nullptr, nullptr);
415  kState1.correctPIM(xi, dt, kGravity, kOmegaCoriolis, false, aH1, aH2);
416  EXPECT(assert_equal(numericalDerivative21(correctPIM, kState1, xi), aH1));
417  EXPECT(assert_equal(numericalDerivative22(correctPIM, kState1, xi), aH2));
418 }
419 
420 /* ************************************************************************* */
421 TEST(NavState, Stream)
422 {
423  NavState state;
424 
425  std::ostringstream os;
426  os << state;
427 
428  string expected;
429  expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\np: 0 0 0\nv: 0 0 0";
430 
431  EXPECT(os.str() == expected);
432 }
433 
434 /* ************************************************************************* */
436  NavState state(Rot3::Identity(), Point3(1, 2, 3), Vector3(1, 2, 3));
437 
438  // Generate the expected output
439  std::string R = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\n";
440  std::string p = "p: 1 2 3\n";
441  std::string v = "v: 1 2 3\n";
442  std::string expected = R + p + v;
443 
445 }
446 
447 /* ************************************************************************* */
448 #ifndef GTSAM_POSE3_EXPMAP
449 TEST(NavState, Retract_first_order) {
450  NavState id;
451  Vector v = Z_9x1;
452  v(0) = 0.3;
453  EXPECT(assert_equal(NavState(R, Point3(0, 0, 0), Vector3(0, 0, 0)),
454  id.retract(v), 1e-2));
455  v(3) = 0.2;
456  v(4) = 0.7;
457  v(5) = -2;
458  v(6) = 3;
459  v(7) = 0.4;
460  v(8) = -2.2;
461  EXPECT(assert_equal(NavState(R, P, V), id.retract(v), 1e-2));
462 }
463 #endif
464 
465 /* ************************************************************************* */
466 TEST(NavState, RetractExpmap) {
467  Vector xi = Z_9x1;
468  xi(0) = 0.3;
470  expected(R, Point3(0, 0, 0), Point3(0, 0, 0));
472  EXPECT(assert_equal(xi, NavState::Logmap(pose), 1e-2));
473 }
474 
475 /* ************************************************************************* */
476 TEST(NavState, Expmap_A_Full) {
477  NavState id;
478  Vector xi = Z_9x1;
479  xi(0) = 0.3;
480  EXPECT(assert_equal(expmap_default<NavState>(id, xi),
481  NavState(R, Point3(0, 0, 0), Point3(0, 0, 0))));
482  xi(3) = -0.2;
483  xi(4) = -0.394742;
484  xi(5) = 2.08998;
485  xi(6) = 0.2;
486  xi(7) = 0.394742;
487  xi(8) = -2.08998;
488 
489  NavState expected(R, -P, P);
490  EXPECT(assert_equal(expected, expmap_default<NavState>(id, xi), 1e-5));
491 }
492 
493 /* ************************************************************************* */
494 TEST(NavState, Expmap_b) {
495  NavState p1(Rot3(), Point3(-100, 0, 0), Point3(100, 0, 0));
496  NavState p2 = p1.retract(
497  (Vector(9) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0).finished());
498  NavState expected(Rot3::Rodrigues(0.0, 0.0, 0.1), Point3(-100.0, 0.0, 0.0),
499  Point3(100.0, 0.0, 0.0));
501 }
502 
503 /* ************************************************************************* */
504 // test case for screw motion in the plane
505 namespace screwNavState {
506 double a = 0.3, c = cos(a), s = sin(a), w = 0.3;
507 Vector xi = (Vector(9) << 0.0, 0.0, w, w, 0.0, 1.0, w, 0.0, 1.0).finished();
508 Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1);
509 Point3 expectedV(0.29552, 0.0446635, 1);
510 Point3 expectedP(0.29552, 0.0446635, 1);
512 } // namespace screwNavState
513 
514 /* ************************************************************************* */
515 // assert that T*exp(xi)*T^-1 is equal to exp(Ad_T(xi))
516 TEST(NavState, Adjoint_full) {
518  Vector xiPrime = T.Adjoint(screwNavState::xi);
520 
522  Vector xiPrime2 = T2.Adjoint(screwNavState::xi);
523  EXPECT(assert_equal(expected2, NavState::Expmap(xiPrime2), 1e-6));
524 
526  Vector xiPrime3 = T3.Adjoint(screwNavState::xi);
527  EXPECT(assert_equal(expected3, NavState::Expmap(xiPrime3), 1e-6));
528 }
529 
530 /* ************************************************************************* */
531 TEST(NavState, Adjoint_compose_full) {
532  // To debug derivatives of compose, assert that
533  // T1*T2*exp(Adjoint(inv(T2),x) = T1*exp(x)*T2
534  const NavState& T1 = T;
535  Vector x =
536  (Vector(9) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8, 0.4, 0.2, 0.8).finished();
538  Vector y = T2.inverse().Adjoint(x);
539  NavState actual = T1 * T2 * NavState::Expmap(y);
540  EXPECT(assert_equal(expected, actual, 1e-6));
541 }
542 
543 /* ************************************************************************* */
544 TEST(NavState, HatAndVee) {
545  // Create a few test vectors
546  Vector9 v1(1, 2, 3, 4, 5, 6, 7, 8, 9);
547  Vector9 v2(0.1, -0.5, 1.0, -1.0, 0.5, 2.0, 0.3, -0.2, 0.8);
548  Vector9 v3 = Vector9::Zero();
549 
550  // Test that Vee(Hat(v)) == v for various inputs
551  EXPECT(assert_equal(v1, NavState::Vee(NavState::Hat(v1))));
552  EXPECT(assert_equal(v2, NavState::Vee(NavState::Hat(v2))));
553  EXPECT(assert_equal(v3, NavState::Vee(NavState::Hat(v3))));
554 
555  // Check the structure of the Lie Algebra element
556  Matrix5 expected;
557  expected << 0, -3, 2, 4, 7,
558  3, 0, -1, 5, 8,
559  -2, 1, 0, 6, 9,
560  0, 0, 0, 0, 0,
561  0, 0, 0, 0, 0;
562 
563  EXPECT(assert_equal(expected, NavState::Hat(v1)));
564 }
565 
566 /* ************************************************************************* */
567 // Checks correct exponential map (Expmap) with brute force matrix exponential
568 TEST(NavState, BruteForceExpmap1) {
569  const Vector9 xi(0, 0, 0, 14, 24, 34, 15, 25, 35);
570  EXPECT(assert_equal(NavState::Expmap(xi), expm<NavState>(xi), 1e-6));
571 }
572 
573 TEST(NavState, BruteForceExpmap2) {
574  const Vector9 xi(0.1, 0.2, 0.3, 0, 0, 0, 0, 0, 0);
575  EXPECT(assert_equal(NavState::Expmap(xi), expm<NavState>(xi), 1e-6));
576 }
577 
578 TEST(NavState, BruteForceExpmap3) {
579  const Vector9 xi(0.1, 0.2, 0.3, 4, 5, 6, 7, 8, 9);
580  EXPECT(assert_equal(NavState::Expmap(xi), expm<NavState>(xi), 1e-6));
581 }
582 
583 /* ************************************************************************* */
584 // assert that T*Hat(xi)*T^-1 is equal to Hat(Ad_T(xi))
585 TEST(NavState, Adjoint_hat)
586 {
587  Matrix5 expected = T.matrix() * NavState::Hat(screwNavState::xi) * T.matrix().inverse();
588  Matrix5 xiprime = NavState::Hat(T.Adjoint(screwNavState::xi));
589  EXPECT(assert_equal(expected, xiprime, 1e-6));
590 
591  Matrix5 expected2 = T2.matrix() * NavState::Hat(screwNavState::xi) * T2.matrix().inverse();
592  Matrix5 xiprime2 = NavState::Hat(T2.Adjoint(screwNavState::xi));
593  EXPECT(assert_equal(expected2, xiprime2, 1e-6));
594 
595  Matrix5 expected3 = T3.matrix() * NavState::Hat(screwNavState::xi) * T3.matrix().inverse();
596  Matrix5 xiprime3 = NavState::Hat(T3.Adjoint(screwNavState::xi));
597  EXPECT(assert_equal(expected3, xiprime3, 1e-6));
598 }
599 
600 /* ************************************************************************* */
601 TEST(NavState, Retract_LocalCoordinates) {
602  Vector9 d;
603  d << 1, 2, 3, 4, 5, 6, 7, 8, 9;
604  d /= 10;
605  const Rot3 R = Rot3::Retract(d.head<3>());
606  NavState t = NavState::Retract(d);
607  EXPECT(assert_equal(d, NavState::LocalCoordinates(t)));
608 }
609 /* ************************************************************************* */
610 TEST(NavState, retract_localCoordinates) {
611  Vector9 d12;
612  d12 << 1, 2, 3, 4, 5, 6, 7, 8, 9;
613  d12 /= 10;
614  NavState t1 = T, t2 = t1.retract(d12);
615  EXPECT(assert_equal(d12, t1.localCoordinates(t2)));
616 }
617 /* ************************************************************************* */
618 TEST(NavState, expmap_logmap) {
619  Vector d12 = Vector9::Constant(0.1);
620  NavState t1 = T, t2 = t1.expmap(d12);
621  EXPECT(assert_equal(d12, t1.logmap(t2)));
622 }
623 
624 /* ************************************************************************* */
625 TEST(NavState, retract_localCoordinates2) {
626  NavState t1 = T;
627  NavState t2 = T3;
629  Vector d12 = t1.localCoordinates(t2);
630  EXPECT(assert_equal(t2, t1.retract(d12)));
631  Vector d21 = t2.localCoordinates(t1);
632  EXPECT(assert_equal(t1, t2.retract(d21)));
633  // NOTE(FRANK): d12 !== -d21 for arbitrary retractions.
634 }
635 /* ************************************************************************* */
636 TEST(NavState, manifold_expmap) {
637  NavState t1 = T;
638  NavState t2 = T3;
640  Vector d12 = t1.logmap(t2);
641  EXPECT(assert_equal(t2, t1.expmap(d12)));
642  Vector d21 = t2.logmap(t1);
643  EXPECT(assert_equal(t1, t2.expmap(d21)));
644 
645  // Check that log(t1,t2)=-log(t2,t1)
646  EXPECT(assert_equal(d12, -d21));
647 }
648 
649 /* ************************************************************************* */
650 TEST(NavState, subgroups) {
651  // Frank - Below only works for correct "Agrawal06iros style expmap
652  // lines in canonical coordinates correspond to Abelian subgroups in SE(3)
653  Vector d =
654  (Vector(9) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8, 0.9).finished();
655  // exp(-d)=inverse(exp(d))
657  // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d)
658  NavState T2 = NavState::Expmap(2 * d);
659  NavState T3 = NavState::Expmap(3 * d);
660  NavState T5 = NavState::Expmap(5 * d);
661  EXPECT(assert_equal(T5, T2 * T3));
662  EXPECT(assert_equal(T5, T3 * T2));
663 }
664 
665 /* ************************************************************************* */
666 TEST(NavState, adjointMap) {
667  Matrix res = NavState::adjointMap(screwNavState::xi);
669  screwNavState::xi(2));
671  screwNavState::xi(5));
673  screwNavState::xi(8));
675  expected << wh, Z_3x3, Z_3x3, vh, wh, Z_3x3, rh, Z_3x3, wh;
677 }
678 
679 /* ************************************************************************* */
680 TEST(NavState, ExpmapDerivative1) {
681  Matrix9 actualH;
682  Vector9 w;
683  w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0;
684  NavState::Expmap(w, actualH);
685 
686  std::function<NavState(const Vector9&)> f = [](const Vector9& w) {
687  return NavState::Expmap(w);
688  };
689  Matrix expectedH =
690  numericalDerivative21<NavState, Vector9, OptionalJacobian<9, 9> >(
691  &NavState::Expmap, w, {});
692  EXPECT(assert_equal(expectedH, actualH));
693 }
694 
695 /* ************************************************************************* */
696 TEST(NavState, LogmapDerivative) {
697  Matrix9 actualH;
698  Vector9 w;
699  w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0;
701  EXPECT(assert_equal(w, NavState::Logmap(p, actualH), 1e-5));
702 
703  std::function<Vector9(const NavState&)> f = [](const NavState& p) {
704  return NavState::Logmap(p);
705  };
706  Matrix expectedH =
707  numericalDerivative21<Vector9, NavState, OptionalJacobian<9, 9> >(
708  &NavState::Logmap, p, {});
709  EXPECT(assert_equal(expectedH, actualH));
710 }
711 
712 //******************************************************************************
713 TEST(NavState, Invariants) {
714  NavState id;
715 
716  EXPECT(check_group_invariants(id, id));
717  EXPECT(check_group_invariants(id, T3));
718  EXPECT(check_group_invariants(T2, id));
719  EXPECT(check_group_invariants(T2, T3));
720 
721  EXPECT(check_manifold_invariants(id, id));
722  EXPECT(check_manifold_invariants(id, T3));
723  EXPECT(check_manifold_invariants(T2, id));
724  EXPECT(check_manifold_invariants(T2, T3));
725 }
726 
727 //******************************************************************************
728 TEST(NavState, LieGroupDerivatives) {
729  NavState id;
730 
735 }
736 
737 //******************************************************************************
738 TEST(NavState, ChartDerivatives) {
739  NavState id;
740  if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) {
741  CHECK_CHART_DERIVATIVES(id, id);
745  }
746 }
747 
748 /* ************************************************************************* */
749 int main() {
750  TestResult tr;
751  return TestRegistry::runAllTests(tr);
752 }
753 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
create
ADT create(const Signature &signature)
Definition: testAlgebraicDecisionTree.cpp:145
gtsam::LieGroup::between
Class between(const Class &g) const
Definition: Lie.h:52
kPose
static const Pose3 kPose(kAttitude, kPosition)
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
screwNavState::expectedP
Point3 expectedP(0.29552, 0.0446635, 1)
T
static const NavState T(R, P2, V2)
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
GTSAM_CONCEPT_TESTABLE_INST
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:176
gtsam::IsMatrixLieGroup
Definition: Lie.h:311
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
kVelocity
static const Velocity3 kVelocity(0.4, 0.5, 0.6)
gtsam::Velocity3
Vector3 Velocity3
Velocity is currently typedef'd to Vector3.
Definition: NavState.h:28
gtsam::assert_print_equal
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Definition: TestableAssertions.h:353
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
kOmegaCoriolis
static const Vector3 kOmegaCoriolis(0.02, 0.03, 0.04)
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
kAttitude
static const Rot3 kAttitude
Definition: testNavState.cpp:35
kPosition
static const Point3 kPosition(1.0, 2.0, 3.0)
screwNavState::xi
Vector xi
Definition: testNavState.cpp:507
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::NavState::AdjointMap
Matrix9 AdjointMap() const
Definition: NavState.cpp:180
gtsam::NavState
Definition: NavState.h:38
gtsam::utils.numerical_derivative.retract
def retract(a, np.ndarray xi)
Definition: numerical_derivative.py:44
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::NavState::bodyVelocity
Velocity3 bodyVelocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:69
initial::nRb
const Rot3 nRb
Definition: testScenarioRunner.cpp:149
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
testLie.h
screwNavState::expected
NavState expected(expectedR, expectedV, expectedP)
res
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Definition: PartialRedux_count.cpp:3
screwNavState::w
double w
Definition: testNavState.cpp:506
os
ofstream os("timeSchurFactors.csv")
gtsam::IsGroup
Definition: Group.h:42
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:381
drot
int BLASFUNC() drot(int *, double *, int *, double *, int *, double *, double *)
gtsam::Rot3::unrotate
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
TestableAssertions.h
Provides additional testing facilities for common data structures.
kState1
static const NavState kState1(kAttitude, kPosition, kVelocity)
gtsam::NavState::correctPIM
Vector9 correctPIM(const Vector9 &pim, double dt, const Vector3 &n_gravity, const std::optional< Vector3 > &omegaCoriolis, bool use2ndOrderCoriolis=false, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
Definition: NavState.cpp:462
dt
static const double dt
Definition: testNavState.cpp:333
main
int main()
Definition: testNavState.cpp:749
P2
static const Point3 P2(3.5, -8.2, 4.2)
gtsam::internal::attitude
Rot3 attitude(const NavState &X, OptionalJacobian< 3, 9 > H)
Definition: navigation/expressions.h:22
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
id
static const Similarity3 id
Definition: testSimilarity3.cpp:44
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::NavState::attitude
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:48
gtsam::NavState::Adjoint
Vector9 Adjoint(const Vector9 &xi_b, OptionalJacobian< 9, 9 > H_this={}, OptionalJacobian< 9, 9 > H_xib={}) const
Definition: NavState.cpp:191
R
static const Rot3 R
Definition: testNavState.cpp:47
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::numericalDerivative32
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:259
gtsam::Pose3
Definition: Pose3.h:37
T2
static const NavState T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2, V2)
GTSAM_CONCEPT_LIE_INST
#define GTSAM_CONCEPT_LIE_INST(T)
Definition: Lie.h:410
M_PI_4
#define M_PI_4
Definition: mconf.h:119
NavState.h
Navigation state composing of attitude, position, and velocity.
kGravity
static const Vector3 kGravity(0, 0, 9.81)
gtsam::numericalDerivative31
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:226
gtsam::internal::velocity
Velocity3 velocity(const NavState &X, OptionalJacobian< 3, 9 > H)
Definition: navigation/expressions.h:28
CHECK_LIE_GROUP_DERIVATIVES
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
bodyVelocity
Vector3 bodyVelocity(const Pose3 &w_t_b, const Vector3 &vec_w, OptionalJacobian< 3, 6 > Hpose={}, OptionalJacobian< 3, 3 > Hvel={})
Definition: testFactorTesting.cpp:29
T5
static const Similarity3 T5(R, P, 10)
Eigen::Triplet< double >
kZeroXi
static const Vector9 kZeroXi
Definition: testNavState.cpp:43
common::state2
static const NavState state2(x2, v2)
screwNavState::expectedV
Point3 expectedV(0.29552, 0.0446635, 1)
kIdentity
static const NavState kIdentity
Definition: testNavState.cpp:39
gtsam::LieGroup::logmap
TangentVector logmap(const Class &g) const
Definition: Lie.h:84
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::NavState::matrix
Matrix5 matrix() const
Definition: NavState.cpp:80
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
screwNavState::c
double c
Definition: testNavState.cpp:506
V2
static const Point3 V2(-6.5, 3.5, 6.2)
P
static const Point3 P(0.2, 0.7, -2)
gtsam::interpolate
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={}, typename MakeOptionalJacobian< T, double >::type Ht={})
Definition: Lie.h:363
pose2
Definition: testFrobeniusFactor.cpp:193
gtsam
traits
Definition: SFMdata.h:40
screwNavState::a
double a
Definition: testNavState.cpp:506
construct
void construct(...)
Definition: init.h:107
gtsam::NavState::equals
bool equals(const NavState &other, double tol=1e-8) const
equals
Definition: NavState.cpp:104
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::NavState::position
const Point3 & position(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:55
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
screwNavState::expectedR
Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1)
TEST
TEST(NavState, Concept)
Definition: testNavState.cpp:56
std
Definition: BFloat16.h:88
origin
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
Definition: gnuplot_common_settings.hh:45
p
float * p
Definition: Tutorial_Map_using.cpp:9
v2
Vector v2
Definition: testSerializationBase.cpp:39
coriolis
std::function< Vector9(const NavState &, const bool &)> coriolis
Definition: testNavState.cpp:334
V
static const Point3 V(3, 0.4, -2.2)
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::internal::position
Point3 position(const NavState &X, OptionalJacobian< 3, 9 > H)
Definition: navigation/expressions.h:25
gtsam::Similarity3::matrix
Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
Definition: Similarity3.cpp:291
gtsam::NavState::velocity
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H={}) const
Definition: NavState.cpp:62
gtsam::testing::between
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::NavState::inverse
NavState inverse() const
inverse transformation with derivatives
Definition: NavState.cpp:110
gtsam::NavState::retract
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Definition: NavState.cpp:309
Inverse
Definition: Inverse.java:13
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
Eigen::Matrix< double, 9, 9 >
screwNavState
Definition: testNavState.cpp:505
v3
Vector v3
Definition: testSerializationBase.cpp:40
gtsam::LieGroup::expmap
Class expmap(const TangentVector &v) const
Definition: Lie.h:78
M_PI
#define M_PI
Definition: mconf.h:117
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::NavState::localCoordinates
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
Definition: NavState.cpp:336
gtsam::NavState::coriolis
Vector9 coriolis(double dt, const Vector3 &omega, bool secondOrder=false, OptionalJacobian< 9, 9 > H={}) const
Compute tangent space contribution due to Coriolis forces.
Definition: NavState.cpp:417
lieProxies.h
Provides convenient mappings of common member functions for testing.
align_3::t
Point2 t(10, 10)
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
GTSAM_CONCEPT_ASSERT
#define GTSAM_CONCEPT_ASSERT(concept)
Definition: base/concepts.h:25
CHECK_CHART_DERIVATIVES
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
v1
Vector v1
Definition: testSerializationBase.cpp:38
ROT3_DEFAULT_COORDINATES_MODE
#define ROT3_DEFAULT_COORDINATES_MODE
Definition: Rot3.h:43
make_changelog.state
state
Definition: make_changelog.py:29
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
T3
static const NavState T3(Rot3::Rodrigues(-90, 0, 0), Point3(5, 6, 7), Point3(1, 2, 3))


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:07:10