testPose3.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 
17 #include <gtsam/geometry/Pose3.h>
18 #include <gtsam/geometry/Pose2.h>
19 #include <gtsam/base/testLie.h>
20 #include <gtsam/base/lieProxies.h>
22 
23 #include <boost/assign/std/vector.hpp> // for operator +=
24 using namespace boost::assign;
25 
27 #include <cmath>
28 
29 using namespace std;
30 using namespace gtsam;
31 
34 
35 static const Point3 P(0.2,0.7,-2);
36 static const Rot3 R = Rot3::Rodrigues(0.3,0,0);
37 static const Point3 P2(3.5,-8.2,4.2);
38 static const Pose3 T(R,P2);
39 static const Pose3 T2(Rot3::Rodrigues(0.3,0.2,0.1),P2);
40 static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3));
41 static const double tol=1e-5;
42 
43 /* ************************************************************************* */
45 {
46  Pose3 pose2 = T3;
47  EXPECT(T3.equals(pose2));
48  Pose3 origin;
49  EXPECT(!T3.equals(origin));
50 }
51 
52 /* ************************************************************************* */
53 TEST( Pose3, constructors)
54 {
55  Pose3 expected(Rot3::Rodrigues(0,0,3),Point3(1,2,0));
56  Pose2 pose2(1,2,3);
57  EXPECT(assert_equal(expected,Pose3(pose2)));
58 }
59 
60 /* ************************************************************************* */
61 #ifndef GTSAM_POSE3_EXPMAP
62 TEST( Pose3, retract_first_order)
63 {
64  Pose3 id;
65  Vector v = Z_6x1;
66  v(0) = 0.3;
67  EXPECT(assert_equal(Pose3(R, Point3(0,0,0)), id.retract(v),1e-2));
68  v(3)=0.2;v(4)=0.7;v(5)=-2;
69  EXPECT(assert_equal(Pose3(R, P),id.retract(v),1e-2));
70 }
71 #endif
72 /* ************************************************************************* */
73 TEST( Pose3, retract_expmap)
74 {
75  Vector v = Z_6x1; v(0) = 0.3;
77  EXPECT(assert_equal(Pose3(R, Point3(0,0,0)), pose, 1e-2));
78  EXPECT(assert_equal(v,Pose3::Logmap(pose),1e-2));
79 }
80 
81 /* ************************************************************************* */
82 TEST( Pose3, expmap_a_full)
83 {
84  Pose3 id;
85  Vector v = Z_6x1;
86  v(0) = 0.3;
87  EXPECT(assert_equal(expmap_default<Pose3>(id, v), Pose3(R, Point3(0,0,0))));
88  v(3)=0.2;v(4)=0.394742;v(5)=-2.08998;
89  EXPECT(assert_equal(Pose3(R, P),expmap_default<Pose3>(id, v),1e-5));
90 }
91 
92 /* ************************************************************************* */
93 TEST( Pose3, expmap_a_full2)
94 {
95  Pose3 id;
96  Vector v = Z_6x1;
97  v(0) = 0.3;
98  EXPECT(assert_equal(expmap_default<Pose3>(id, v), Pose3(R, Point3(0,0,0))));
99  v(3)=0.2;v(4)=0.394742;v(5)=-2.08998;
100  EXPECT(assert_equal(Pose3(R, P),expmap_default<Pose3>(id, v),1e-5));
101 }
102 
103 /* ************************************************************************* */
104 TEST(Pose3, expmap_b)
105 {
106  Pose3 p1(Rot3(), Point3(100, 0, 0));
107  Pose3 p2 = p1.retract((Vector(6) << 0.0, 0.0, 0.1, 0.0, 0.0, 0.0).finished());
108  Pose3 expected(Rot3::Rodrigues(0.0, 0.0, 0.1), Point3(100.0, 0.0, 0.0));
109  EXPECT(assert_equal(expected, p2,1e-2));
110 }
111 
112 /* ************************************************************************* */
113 // test case for screw motion in the plane
114 namespace screwPose3 {
115  double a=0.3, c=cos(a), s=sin(a), w=0.3;
116  Vector xi = (Vector(6) << 0.0, 0.0, w, w, 0.0, 1.0).finished();
117  Rot3 expectedR(c, -s, 0, s, c, 0, 0, 0, 1);
118  Point3 expectedT(0.29552, 0.0446635, 1);
120 }
121 
122 /* ************************************************************************* */
123 // Checks correct exponential map (Expmap) with brute force matrix exponential
124 TEST(Pose3, expmap_c_full)
125 {
128 }
129 
130 /* ************************************************************************* */
131 // assert that T*exp(xi)*T^-1 is equal to exp(Ad_T(xi))
132 TEST(Pose3, Adjoint_full)
133 {
134  Pose3 expected = T * Pose3::Expmap(screwPose3::xi) * T.inverse();
135  Vector xiprime = T.Adjoint(screwPose3::xi);
136  EXPECT(assert_equal(expected, Pose3::Expmap(xiprime), 1e-6));
137 
138  Pose3 expected2 = T2 * Pose3::Expmap(screwPose3::xi) * T2.inverse();
139  Vector xiprime2 = T2.Adjoint(screwPose3::xi);
140  EXPECT(assert_equal(expected2, Pose3::Expmap(xiprime2), 1e-6));
141 
142  Pose3 expected3 = T3 * Pose3::Expmap(screwPose3::xi) * T3.inverse();
143  Vector xiprime3 = T3.Adjoint(screwPose3::xi);
144  EXPECT(assert_equal(expected3, Pose3::Expmap(xiprime3), 1e-6));
145 }
146 
147 /* ************************************************************************* */
148 // assert that T*wedge(xi)*T^-1 is equal to wedge(Ad_T(xi))
149 TEST(Pose3, Adjoint_hat)
150 {
151  auto hat = [](const Vector& xi) { return ::wedge<Pose3>(xi); };
152  Matrix4 expected = T.matrix() * hat(screwPose3::xi) * T.matrix().inverse();
153  Matrix4 xiprime = hat(T.Adjoint(screwPose3::xi));
154  EXPECT(assert_equal(expected, xiprime, 1e-6));
155 
156  Matrix4 expected2 = T2.matrix() * hat(screwPose3::xi) * T2.matrix().inverse();
157  Matrix4 xiprime2 = hat(T2.Adjoint(screwPose3::xi));
158  EXPECT(assert_equal(expected2, xiprime2, 1e-6));
159 
160  Matrix4 expected3 = T3.matrix() * hat(screwPose3::xi) * T3.matrix().inverse();
161  Matrix4 xiprime3 = hat(T3.Adjoint(screwPose3::xi));
162  EXPECT(assert_equal(expected3, xiprime3, 1e-6));
163 }
164 
165 /* ************************************************************************* */
168  Vector w = xi.head(3);
169  Vector v = xi.tail(3);
170  double t = w.norm();
171  if (t < 1e-5)
172  return Pose3(Rot3(), Point3(v));
173  else {
174  Matrix W = skewSymmetric(w/t);
175  Matrix A = I_3x3 + ((1 - cos(t)) / t) * W + ((t - sin(t)) / t) * (W * W);
176  return Pose3(Rot3::Expmap (w), Point3(A * v));
177  }
178 }
179 
180 /* ************************************************************************* */
181 TEST(Pose3, expmaps_galore_full)
182 {
183  Vector xi; Pose3 actual;
184  xi = (Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
185  actual = Pose3::Expmap(xi);
186  EXPECT(assert_equal(expm<Pose3>(xi), actual,1e-6));
187  EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-6));
188  EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-6));
189 
190  xi = (Vector(6) << 0.1, -0.2, 0.3, -0.4, 0.5, -0.6).finished();
191  for (double theta=1.0;0.3*theta<=M_PI;theta*=2) {
192  Vector txi = xi*theta;
193  actual = Pose3::Expmap(txi);
194  EXPECT(assert_equal(expm<Pose3>(txi,30), actual,1e-6));
195  EXPECT(assert_equal(Agrawal06iros(txi), actual,1e-6));
196  Vector log = Pose3::Logmap(actual);
197  EXPECT(assert_equal(actual, Pose3::Expmap(log),1e-6));
198  EXPECT(assert_equal(txi,log,1e-6)); // not true once wraps
199  }
200 
201  // Works with large v as well, but expm needs 10 iterations!
202  xi = (Vector(6) << 0.2, 0.3, -0.8, 100.0, 120.0, -60.0).finished();
203  actual = Pose3::Expmap(xi);
204  EXPECT(assert_equal(expm<Pose3>(xi,10), actual,1e-5));
205  EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-9));
206  EXPECT(assert_equal(xi, Pose3::Logmap(actual),1e-9));
207 }
208 
209 /* ************************************************************************* */
210 // Check translation and its pushforward
211 TEST(Pose3, translation) {
212  Matrix actualH;
213  EXPECT(assert_equal(Point3(3.5, -8.2, 4.2), T.translation(actualH), 1e-8));
214 
215  Matrix numericalH = numericalDerivative11<Point3, Pose3>(
216  boost::bind(&Pose3::translation, _1, boost::none), T);
217  EXPECT(assert_equal(numericalH, actualH, 1e-6));
218 }
219 
220 /* ************************************************************************* */
221 // Check rotation and its pushforward
223  Matrix actualH;
224  EXPECT(assert_equal(R, T.rotation(actualH), 1e-8));
225 
226  Matrix numericalH = numericalDerivative11<Rot3, Pose3>(
227  boost::bind(&Pose3::rotation, _1, boost::none), T);
228  EXPECT(assert_equal(numericalH, actualH, 1e-6));
229 }
230 
231 /* ************************************************************************* */
232 TEST(Pose3, Adjoint_compose_full)
233 {
234  // To debug derivatives of compose, assert that
235  // T1*T2*exp(Adjoint(inv(T2),x) = T1*exp(x)*T2
236  const Pose3& T1 = T;
237  Vector x = (Vector(6) << 0.1, 0.1, 0.1, 0.4, 0.2, 0.8).finished();
238  Pose3 expected = T1 * Pose3::Expmap(x) * T2;
239  Vector y = T2.inverse().Adjoint(x);
240  Pose3 actual = T1 * T2 * Pose3::Expmap(y);
241  EXPECT(assert_equal(expected, actual, 1e-6));
242 }
243 
244 /* ************************************************************************* */
245 // Check compose and its pushforward
246 // NOTE: testing::compose<Pose3>(t1,t2) = t1.compose(t2) (see lieProxies.h)
248 {
249  Matrix actual = (T2*T2).matrix();
251  EXPECT(assert_equal(actual,expected,1e-8));
252 
253  Matrix actualDcompose1, actualDcompose2;
254  T2.compose(T2, actualDcompose1, actualDcompose2);
255 
256  Matrix numericalH1 = numericalDerivative21(testing::compose<Pose3>, T2, T2);
257  EXPECT(assert_equal(numericalH1,actualDcompose1,5e-3));
258  EXPECT(assert_equal(T2.inverse().AdjointMap(),actualDcompose1,5e-3));
259 
260  Matrix numericalH2 = numericalDerivative22(testing::compose<Pose3>, T2, T2);
261  EXPECT(assert_equal(numericalH2,actualDcompose2,1e-4));
262 }
263 
264 /* ************************************************************************* */
265 // Check compose and its pushforward, another case
266 TEST( Pose3, compose2 )
267 {
268  const Pose3& T1 = T;
269  Matrix actual = (T1*T2).matrix();
270  Matrix expected = T1.matrix()*T2.matrix();
271  EXPECT(assert_equal(actual,expected,1e-8));
272 
273  Matrix actualDcompose1, actualDcompose2;
274  T1.compose(T2, actualDcompose1, actualDcompose2);
275 
276  Matrix numericalH1 = numericalDerivative21(testing::compose<Pose3>, T1, T2);
277  EXPECT(assert_equal(numericalH1,actualDcompose1,5e-3));
278  EXPECT(assert_equal(T2.inverse().AdjointMap(),actualDcompose1,5e-3));
279 
280  Matrix numericalH2 = numericalDerivative22(testing::compose<Pose3>, T1, T2);
281  EXPECT(assert_equal(numericalH2,actualDcompose2,1e-5));
282 }
283 
284 /* ************************************************************************* */
286 {
287  Matrix actualDinverse;
288  Matrix actual = T.inverse(actualDinverse).matrix();
289  Matrix expected = T.matrix().inverse();
290  EXPECT(assert_equal(actual,expected,1e-8));
291 
292  Matrix numericalH = numericalDerivative11(testing::inverse<Pose3>, T);
293  EXPECT(assert_equal(numericalH,actualDinverse,5e-3));
294  EXPECT(assert_equal(-T.AdjointMap(),actualDinverse,5e-3));
295 }
296 
297 /* ************************************************************************* */
298 TEST( Pose3, inverseDerivatives2)
299 {
300  Rot3 R = Rot3::Rodrigues(0.3,0.4,-0.5);
301  Point3 t(3.5,-8.2,4.2);
302  Pose3 T(R,t);
303 
304  Matrix numericalH = numericalDerivative11(testing::inverse<Pose3>, T);
305  Matrix actualDinverse;
306  T.inverse(actualDinverse);
307  EXPECT(assert_equal(numericalH,actualDinverse,5e-3));
308  EXPECT(assert_equal(-T.AdjointMap(),actualDinverse,5e-3));
309 }
310 
311 /* ************************************************************************* */
312 TEST( Pose3, compose_inverse)
313 {
314  Matrix actual = (T*T.inverse()).matrix();
315  Matrix expected = I_4x4;
316  EXPECT(assert_equal(actual,expected,1e-8));
317 }
318 
319 /* ************************************************************************* */
321  return pose.transformFrom(point);
322 }
323 TEST(Pose3, Dtransform_from1_a) {
324  Matrix actualDtransform_from1;
325  T.transformFrom(P, actualDtransform_from1, boost::none);
327  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
328 }
329 
330 TEST(Pose3, Dtransform_from1_b) {
331  Pose3 origin;
332  Matrix actualDtransform_from1;
333  origin.transformFrom(P, actualDtransform_from1, boost::none);
334  Matrix numerical = numericalDerivative21(transformFrom_, origin, P);
335  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
336 }
337 
338 TEST(Pose3, Dtransform_from1_c) {
339  Point3 origin(0, 0, 0);
340  Pose3 T0(R, origin);
341  Matrix actualDtransform_from1;
342  T0.transformFrom(P, actualDtransform_from1, boost::none);
343  Matrix numerical = numericalDerivative21(transformFrom_, T0, P);
344  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
345 }
346 
347 TEST(Pose3, Dtransform_from1_d) {
348  Rot3 I;
349  Point3 t0(100, 0, 0);
350  Pose3 T0(I, t0);
351  Matrix actualDtransform_from1;
352  T0.transformFrom(P, actualDtransform_from1, boost::none);
353  // print(computed, "Dtransform_from1_d computed:");
354  Matrix numerical = numericalDerivative21(transformFrom_, T0, P);
355  // print(numerical, "Dtransform_from1_d numerical:");
356  EXPECT(assert_equal(numerical, actualDtransform_from1, 1e-8));
357 }
358 
359 /* ************************************************************************* */
360 TEST(Pose3, Dtransform_from2) {
361  Matrix actualDtransform_from2;
362  T.transformFrom(P, boost::none, actualDtransform_from2);
364  EXPECT(assert_equal(numerical, actualDtransform_from2, 1e-8));
365 }
366 
367 /* ************************************************************************* */
369  return pose.transformTo(point);
370 }
371 TEST(Pose3, Dtransform_to1) {
372  Matrix computed;
373  T.transformTo(P, computed, boost::none);
375  EXPECT(assert_equal(numerical, computed, 1e-8));
376 }
377 
378 /* ************************************************************************* */
379 TEST(Pose3, Dtransform_to2) {
380  Matrix computed;
381  T.transformTo(P, boost::none, computed);
383  EXPECT(assert_equal(numerical, computed, 1e-8));
384 }
385 
386 /* ************************************************************************* */
387 TEST(Pose3, transform_to_with_derivatives) {
388  Matrix actH1, actH2;
389  T.transformTo(P, actH1, actH2);
392  EXPECT(assert_equal(expH1, actH1, 1e-8));
393  EXPECT(assert_equal(expH2, actH2, 1e-8));
394 }
395 
396 /* ************************************************************************* */
397 TEST(Pose3, transform_from_with_derivatives) {
398  Matrix actH1, actH2;
399  T.transformFrom(P, actH1, actH2);
402  EXPECT(assert_equal(expH1, actH1, 1e-8));
403  EXPECT(assert_equal(expH2, actH2, 1e-8));
404 }
405 
406 /* ************************************************************************* */
407 TEST(Pose3, transform_to_translate) {
408  Point3 actual =
409  Pose3(Rot3(), Point3(1, 2, 3)).transformTo(Point3(10., 20., 30.));
410  Point3 expected(9., 18., 27.);
411  EXPECT(assert_equal(expected, actual));
412 }
413 
414 /* ************************************************************************* */
415 TEST(Pose3, transform_to_rotate) {
416  Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(0, 0, 0));
417  Point3 actual = transform.transformTo(Point3(2, 1, 10));
418  Point3 expected(-1, 2, 10);
419  EXPECT(assert_equal(expected, actual, 0.001));
420 }
421 
422 /* ************************************************************************* */
423 // Check transformPoseFrom and its pushforward
424 Pose3 transformPoseFrom_(const Pose3& wTa, const Pose3& aTb) {
425  return wTa.transformPoseFrom(aTb);
426 }
427 
428 TEST(Pose3, transformPoseFrom)
429 {
430  Matrix actual = (T2*T2).matrix();
432  EXPECT(assert_equal(actual, expected, 1e-8));
433 
434  Matrix H1, H2;
435  T2.transformPoseFrom(T2, H1, H2);
436 
438  EXPECT(assert_equal(numericalH1, H1, 5e-3));
439  EXPECT(assert_equal(T2.inverse().AdjointMap(), H1, 5e-3));
440 
442  EXPECT(assert_equal(numericalH2, H2, 1e-4));
443 }
444 
445 /* ************************************************************************* */
447  Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(2, 4, 0));
448  Point3 actual = transform.transformTo(Point3(3, 2, 10));
449  Point3 expected(2, 1, 10);
450  EXPECT(assert_equal(expected, actual, 0.001));
451 }
452 
454  return pose.transformPoseTo(pose2);
455 }
456 
457 /* ************************************************************************* */
458 TEST(Pose3, transformPoseTo) {
459  Pose3 origin = T.transformPoseTo(T);
461 }
462 
463 /* ************************************************************************* */
464 TEST(Pose3, transformPoseTo_with_derivatives) {
465  Matrix actH1, actH2;
466  Pose3 res = T.transformPoseTo(T2, actH1, actH2);
467  EXPECT(assert_equal(res, T.inverse().compose(T2)));
468 
471  EXPECT(assert_equal(expH1, actH1, 1e-8));
472  EXPECT(assert_equal(expH2, actH2, 1e-8));
473 }
474 
475 /* ************************************************************************* */
476 TEST(Pose3, transformPoseTo_with_derivatives2) {
477  Matrix actH1, actH2;
478  Pose3 res = T.transformPoseTo(T3, actH1, actH2);
479  EXPECT(assert_equal(res, T.inverse().compose(T3)));
480 
483  EXPECT(assert_equal(expH1, actH1, 1e-8));
484  EXPECT(assert_equal(expH2, actH2, 1e-8));
485 }
486 
487 /* ************************************************************************* */
489  Point3 actual = T3.transformFrom(Point3(0, 0, 0));
490  Point3 expected = Point3(1., 2., 3.);
491  EXPECT(assert_equal(expected, actual));
492 }
493 
494 /* ************************************************************************* */
495 TEST(Pose3, transform_roundtrip) {
496  Point3 actual = T3.transformFrom(T3.transformTo(Point3(12., -0.11, 7.0)));
497  Point3 expected(12., -0.11, 7.0);
498  EXPECT(assert_equal(expected, actual));
499 }
500 
501 /* ************************************************************************* */
502 TEST(Pose3, Retract_LocalCoordinates)
503 {
504  Vector6 d;
505  d << 1,2,3,4,5,6; d/=10;
506  const Rot3 R = Rot3::Retract(d.head<3>());
507  Pose3 t = Pose3::Retract(d);
508  EXPECT(assert_equal(d, Pose3::LocalCoordinates(t)));
509 }
510 /* ************************************************************************* */
511 TEST(Pose3, retract_localCoordinates)
512 {
513  Vector6 d12;
514  d12 << 1,2,3,4,5,6; d12/=10;
515  Pose3 t1 = T, t2 = t1.retract(d12);
516  EXPECT(assert_equal(d12, t1.localCoordinates(t2)));
517 }
518 /* ************************************************************************* */
519 TEST(Pose3, expmap_logmap)
520 {
521  Vector d12 = Vector6::Constant(0.1);
522  Pose3 t1 = T, t2 = t1.expmap(d12);
523  EXPECT(assert_equal(d12, t1.logmap(t2)));
524 }
525 
526 /* ************************************************************************* */
527 TEST(Pose3, retract_localCoordinates2)
528 {
529  Pose3 t1 = T;
530  Pose3 t2 = T3;
531  Pose3 origin;
532  Vector d12 = t1.localCoordinates(t2);
533  EXPECT(assert_equal(t2, t1.retract(d12)));
534  Vector d21 = t2.localCoordinates(t1);
535  EXPECT(assert_equal(t1, t2.retract(d21)));
536  // TODO(hayk): This currently fails!
537  // EXPECT(assert_equal(d12, -d21));
538 }
539 /* ************************************************************************* */
540 TEST(Pose3, manifold_expmap)
541 {
542  Pose3 t1 = T;
543  Pose3 t2 = T3;
544  Pose3 origin;
545  Vector d12 = t1.logmap(t2);
546  EXPECT(assert_equal(t2, t1.expmap(d12)));
547  Vector d21 = t2.logmap(t1);
548  EXPECT(assert_equal(t1, t2.expmap(d21)));
549 
550  // Check that log(t1,t2)=-log(t2,t1)
551  EXPECT(assert_equal(d12,-d21));
552 }
553 
554 /* ************************************************************************* */
555 TEST(Pose3, subgroups)
556 {
557  // Frank - Below only works for correct "Agrawal06iros style expmap
558  // lines in canonical coordinates correspond to Abelian subgroups in SE(3)
559  Vector d = (Vector(6) << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6).finished();
560  // exp(-d)=inverse(exp(d))
562  // exp(5d)=exp(2*d+3*d)=exp(2*d)exp(3*d)=exp(3*d)exp(2*d)
563  Pose3 T2 = Pose3::Expmap(2*d);
564  Pose3 T3 = Pose3::Expmap(3*d);
565  Pose3 T5 = Pose3::Expmap(5*d);
566  EXPECT(assert_equal(T5,T2*T3));
567  EXPECT(assert_equal(T5,T3*T2));
568 }
569 
570 /* ************************************************************************* */
572 {
573  Pose3 expected = T2.inverse() * T3;
574  Matrix actualDBetween1,actualDBetween2;
575  Pose3 actual = T2.between(T3, actualDBetween1,actualDBetween2);
576  EXPECT(assert_equal(expected,actual));
577 
578  Matrix numericalH1 = numericalDerivative21(testing::between<Pose3> , T2, T3);
579  EXPECT(assert_equal(numericalH1,actualDBetween1,5e-3));
580 
581  Matrix numericalH2 = numericalDerivative22(testing::between<Pose3> , T2, T3);
582  EXPECT(assert_equal(numericalH2,actualDBetween2,1e-5));
583 }
584 
585 /* ************************************************************************* */
586 // some shared test values - pulled from equivalent test in Pose2
587 Point3 l1(1, 0, 0), l2(1, 1, 0), l3(2, 2, 0), l4(1, 4,-4);
588 Pose3 x1, x2(Rot3::Ypr(0.0, 0.0, 0.0), l2), x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2);
589 Pose3
590  xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0)),
591  xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0)),
592  xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0)),
593  xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4));
594 
595 /* ************************************************************************* */
596 double range_proxy(const Pose3& pose, const Point3& point) {
597  return pose.range(point);
598 }
599 TEST( Pose3, range )
600 {
601  Matrix expectedH1, actualH1, expectedH2, actualH2;
602 
603  // establish range is indeed zero
604  EXPECT_DOUBLES_EQUAL(1,x1.range(l1),1e-9);
605 
606  // establish range is indeed sqrt2
607  EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(l2),1e-9);
608 
609  // Another pair
610  double actual23 = x2.range(l3, actualH1, actualH2);
611  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
612 
613  // Check numerical derivatives
614  expectedH1 = numericalDerivative21(range_proxy, x2, l3);
615  expectedH2 = numericalDerivative22(range_proxy, x2, l3);
616  EXPECT(assert_equal(expectedH1,actualH1));
617  EXPECT(assert_equal(expectedH2,actualH2));
618 
619  // Another test
620  double actual34 = x3.range(l4, actualH1, actualH2);
621  EXPECT_DOUBLES_EQUAL(5,actual34,1e-9);
622 
623  // Check numerical derivatives
624  expectedH1 = numericalDerivative21(range_proxy, x3, l4);
625  expectedH2 = numericalDerivative22(range_proxy, x3, l4);
626  EXPECT(assert_equal(expectedH1,actualH1));
627  EXPECT(assert_equal(expectedH2,actualH2));
628 }
629 
630 /* ************************************************************************* */
631 double range_pose_proxy(const Pose3& pose, const Pose3& point) {
632  return pose.range(point);
633 }
634 TEST( Pose3, range_pose )
635 {
636  Matrix expectedH1, actualH1, expectedH2, actualH2;
637 
638  // establish range is indeed zero
639  EXPECT_DOUBLES_EQUAL(1,x1.range(xl1),1e-9);
640 
641  // establish range is indeed sqrt2
642  EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(xl2),1e-9);
643 
644  // Another pair
645  double actual23 = x2.range(xl3, actualH1, actualH2);
646  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
647 
648  // Check numerical derivatives
651  EXPECT(assert_equal(expectedH1,actualH1));
652  EXPECT(assert_equal(expectedH2,actualH2));
653 
654  // Another test
655  double actual34 = x3.range(xl4, actualH1, actualH2);
656  EXPECT_DOUBLES_EQUAL(5,actual34,1e-9);
657 
658  // Check numerical derivatives
661  EXPECT(assert_equal(expectedH1,actualH1));
662  EXPECT(assert_equal(expectedH2,actualH2));
663 }
664 
665 /* ************************************************************************* */
667  return pose.bearing(point);
668 }
670  Matrix expectedH1, actualH1, expectedH2, actualH2;
671  EXPECT(assert_equal(Unit3(1, 0, 0), x1.bearing(l1, actualH1, actualH2), 1e-9));
672 
673  // Check numerical derivatives
674  expectedH1 = numericalDerivative21(bearing_proxy, x1, l1);
675  expectedH2 = numericalDerivative22(bearing_proxy, x1, l1);
676  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
677  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
678 }
679 
680 TEST(Pose3, Bearing2) {
681  Matrix expectedH1, actualH1, expectedH2, actualH2;
682  EXPECT(assert_equal(Unit3(0,0.6,-0.8), x2.bearing(l4, actualH1, actualH2), 1e-9));
683 
684  // Check numerical derivatives
685  expectedH1 = numericalDerivative21(bearing_proxy, x2, l4);
686  expectedH2 = numericalDerivative22(bearing_proxy, x2, l4);
687  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
688  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
689 }
690 
691 TEST(Pose3, PoseToPoseBearing) {
692  Matrix expectedH1, actualH1, expectedH2, actualH2, H2block;
693  EXPECT(assert_equal(Unit3(0,1,0), xl1.bearing(xl2, actualH1, actualH2), 1e-9));
694 
695  // Check numerical derivatives
696  expectedH1 = numericalDerivative21(bearing_proxy, xl1, l2);
697 
698  // Since the second pose is treated as a point, the value calculated by
699  // numericalDerivative22 only depends on the position of the pose. Here, we
700  // calculate the Jacobian w.r.t. the second pose's position, and then augment
701  // that with zeroes in the block that is w.r.t. the second pose's
702  // orientation.
704  expectedH2 = Matrix(2, 6);
705  expectedH2.setZero();
706  expectedH2.block<2, 3>(0, 3) = H2block;
707 
708  EXPECT(assert_equal(expectedH1, actualH1, 1e-5));
709  EXPECT(assert_equal(expectedH2, actualH2, 1e-5));
710 }
711 
712 /* ************************************************************************* */
713 TEST( Pose3, unicycle )
714 {
715  // velocity in X should be X in inertial frame, rather than global frame
716  Vector x_step = Vector::Unit(6,3)*1.0;
717  EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), l1), expmap_default<Pose3>(x1, x_step), tol));
718  EXPECT(assert_equal(Pose3(Rot3::Ypr(0,0,0), Point3(2,1,0)), expmap_default<Pose3>(x2, x_step), tol));
719  EXPECT(assert_equal(Pose3(Rot3::Ypr(M_PI/4.0,0,0), Point3(2,2,0)), expmap_default<Pose3>(x3, sqrt(2.0) * x_step), tol));
720 }
721 
722 /* ************************************************************************* */
723 TEST( Pose3, adjointMap) {
724  Matrix res = Pose3::adjointMap(screwPose3::xi);
727  Matrix6 expected;
728  expected << wh, Z_3x3, vh, wh;
729  EXPECT(assert_equal(expected,res,1e-5));
730 }
731 
732 /* ************************************************************************* */
733 TEST(Pose3, Align1) {
734  Pose3 expected(Rot3(), Point3(10,10,0));
735 
736  vector<Point3Pair> correspondences;
737  Point3Pair ab1(make_pair(Point3(10,10,0), Point3(0,0,0)));
738  Point3Pair ab2(make_pair(Point3(30,20,0), Point3(20,10,0)));
739  Point3Pair ab3(make_pair(Point3(20,30,0), Point3(10,20,0)));
740  correspondences += ab1, ab2, ab3;
741 
742  boost::optional<Pose3> actual = Pose3::Align(correspondences);
743  EXPECT(assert_equal(expected, *actual));
744 }
745 
746 /* ************************************************************************* */
747 TEST(Pose3, Align2) {
748  Point3 t(20,10,5);
749  Rot3 R = Rot3::RzRyRx(0.3, 0.2, 0.1);
750  Pose3 expected(R, t);
751 
752  vector<Point3Pair> correspondences;
753  Point3 p1(0,0,1), p2(10,0,2), p3(20,-10,30);
754  Point3 q1 = expected.transformFrom(p1),
755  q2 = expected.transformFrom(p2),
756  q3 = expected.transformFrom(p3);
757  Point3Pair ab1(make_pair(q1, p1));
758  Point3Pair ab2(make_pair(q2, p2));
759  Point3Pair ab3(make_pair(q3, p3));
760  correspondences += ab1, ab2, ab3;
761 
762  boost::optional<Pose3> actual = Pose3::Align(correspondences);
763  EXPECT(assert_equal(expected, *actual, 1e-5));
764 }
765 
766 /* ************************************************************************* */
767 TEST( Pose3, ExpmapDerivative1) {
768  Matrix6 actualH;
769  Vector6 w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
770  Pose3::Expmap(w,actualH);
771  Matrix expectedH = numericalDerivative21<Pose3, Vector6,
772  OptionalJacobian<6, 6> >(&Pose3::Expmap, w, boost::none);
773  EXPECT(assert_equal(expectedH, actualH));
774 }
775 
776 /* ************************************************************************* */
777 TEST(Pose3, ExpmapDerivative2) {
778  // Iserles05an (Lie-group Methods) says:
779  // scalar is easy: d exp(a(t)) / dt = exp(a(t)) a'(t)
780  // matrix is hard: d exp(A(t)) / dt = exp(A(t)) dexp[-A(t)] A'(t)
781  // where A(t): T -> se(3) is a trajectory in the tangent space of SE(3)
782  // and dexp[A] is a linear map from 4*4 to 4*4 derivatives of se(3)
783  // Hence, the above matrix equation is typed: 4*4 = SE(3) * linear_map(4*4)
784 
785  // In GTSAM, we don't work with the Lie-algebra elements A directly, but with 6-vectors.
786  // xi is easy: d Expmap(xi(t)) / dt = ExmapDerivative[xi(t)] * xi'(t)
787 
788  // Let's verify the above formula.
789 
790  auto xi = [](double t) {
791  Vector6 v;
792  v << 2 * t, sin(t), 4 * t * t, 2 * t, sin(t), 4 * t * t;
793  return v;
794  };
795  auto xi_dot = [](double t) {
796  Vector6 v;
797  v << 2, cos(t), 8 * t, 2, cos(t), 8 * t;
798  return v;
799  };
800 
801  // We define a function T
802  auto T = [xi](double t) { return Pose3::Expmap(xi(t)); };
803 
804  for (double t = -2.0; t < 2.0; t += 0.3) {
805  const Matrix expected = numericalDerivative11<Pose3, double>(T, t);
806  const Matrix actual = Pose3::ExpmapDerivative(xi(t)) * xi_dot(t);
807  CHECK(assert_equal(expected, actual, 1e-7));
808  }
809 }
810 
811 TEST( Pose3, ExpmapDerivativeQr) {
812  Vector6 w = Vector6::Random();
813  w.head<3>().normalize();
814  w.head<3>() = w.head<3>() * 0.9e-2;
815  Matrix3 actualQr = Pose3::ComputeQforExpmapDerivative(w, 0.01);
816  Matrix expectedH = numericalDerivative21<Pose3, Vector6,
817  OptionalJacobian<6, 6> >(&Pose3::Expmap, w, boost::none);
818  Matrix3 expectedQr = expectedH.bottomLeftCorner<3, 3>();
819  EXPECT(assert_equal(expectedQr, actualQr, 1e-6));
820 }
821 
822 /* ************************************************************************* */
823 TEST( Pose3, LogmapDerivative) {
824  Matrix6 actualH;
825  Vector6 w; w << 0.1, 0.2, 0.3, 4.0, 5.0, 6.0;
826  Pose3 p = Pose3::Expmap(w);
827  EXPECT(assert_equal(w, Pose3::Logmap(p,actualH), 1e-5));
828  Matrix expectedH = numericalDerivative21<Vector6, Pose3,
829  OptionalJacobian<6, 6> >(&Pose3::Logmap, p, boost::none);
830  EXPECT(assert_equal(expectedH, actualH));
831 }
832 
833 /* ************************************************************************* */
834 Vector6 testDerivAdjoint(const Vector6& xi, const Vector6& v) {
835  return Pose3::adjointMap(xi) * v;
836 }
837 
840 
841  Matrix actualH;
843 
844  Matrix numericalH = numericalDerivative21<Vector6, Vector6, Vector6>(
846 
847  EXPECT(assert_equal(expected,actual,1e-5));
848  EXPECT(assert_equal(numericalH,actualH,1e-5));
849 }
850 
851 /* ************************************************************************* */
852 Vector6 testDerivAdjointTranspose(const Vector6& xi, const Vector6& v) {
853  return Pose3::adjointMap(xi).transpose() * v;
854 }
855 
856 TEST( Pose3, adjointTranspose) {
857  Vector xi = (Vector(6) << 0.01, 0.02, 0.03, 1.0, 2.0, 3.0).finished();
858  Vector v = (Vector(6) << 0.04, 0.05, 0.06, 4.0, 5.0, 6.0).finished();
860 
861  Matrix actualH;
862  Vector actual = Pose3::adjointTranspose(xi, v, actualH);
863 
864  Matrix numericalH = numericalDerivative21<Vector6, Vector6, Vector6>(
866 
867  EXPECT(assert_equal(expected,actual,1e-15));
868  EXPECT(assert_equal(numericalH,actualH,1e-5));
869 }
870 
871 /* ************************************************************************* */
873  std::ostringstream os;
874  os << Pose3();
875 
876  string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 0 0 0";
877  EXPECT(os.str() == expected);
878 }
879 
880 //******************************************************************************
881 TEST(Pose3 , Invariants) {
882  Pose3 id;
883 
884  EXPECT(check_group_invariants(id,id));
885  EXPECT(check_group_invariants(id,T3));
886  EXPECT(check_group_invariants(T2,id));
887  EXPECT(check_group_invariants(T2,T3));
888 
889  EXPECT(check_manifold_invariants(id,id));
890  EXPECT(check_manifold_invariants(id,T3));
891  EXPECT(check_manifold_invariants(T2,id));
892  EXPECT(check_manifold_invariants(T2,T3));
893 }
894 
895 //******************************************************************************
896 TEST(Pose3 , LieGroupDerivatives) {
897  Pose3 id;
898 
903 }
904 
905 //******************************************************************************
906 TEST(Pose3 , ChartDerivatives) {
907  Pose3 id;
908  if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) {
913  }
914 }
915 
916 //******************************************************************************
917 #include "testPoseAdjointMap.h"
918 
919 TEST(Pose3, TransformCovariance6MapTo2d) {
920  // Create 3d scenarios that map to 2d configurations and compare with Pose2 results.
921  using namespace test_pose_adjoint_map;
922 
923  Vector3 s2{0.1, 0.3, 0.7};
924  Pose2 p2{1.1, 1.5, 31. * degree};
925  auto cov2 = FullCovarianceFromSigmas<Pose2>(s2);
926  auto transformed2 = TransformCovariance<Pose2>{p2}(cov2);
927 
928  auto match_cov3_to_cov2 = [&](int spatial_axis0, int spatial_axis1, int r_axis,
929  const Pose2::Jacobian &cov2, const Pose3::Jacobian &cov3) -> void
930  {
932  Vector3{cov2.diagonal()},
933  Vector3{cov3(spatial_axis0, spatial_axis0), cov3(spatial_axis1, spatial_axis1), cov3(r_axis, r_axis)}));
935  Vector3{cov2(1, 0), cov2(2, 0), cov2(2, 1)},
936  Vector3{cov3(spatial_axis1, spatial_axis0), cov3(r_axis, spatial_axis0), cov3(r_axis, spatial_axis1)}));
937  };
938 
939  // rotate around x axis
940  {
941  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << s2(2), 0., 0., 0., s2(0), s2(1)).finished());
942  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(p2.theta(), 0., 0.), {0., p2.x(), p2.y()}}}(cov3);
943  match_cov3_to_cov2(4, 5, 0, transformed2, transformed3);
944  }
945 
946  // rotate around y axis
947  {
948  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., s2(2), 0., s2(1), 0., s2(0)).finished());
949  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., p2.theta(), 0.), {p2.y(), 0., p2.x()}}}(cov3);
950  match_cov3_to_cov2(5, 3, 1, transformed2, transformed3);
951  }
952 
953  // rotate around z axis
954  {
955  auto cov3 = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0., 0., s2(2), s2(0), s2(1), 0.).finished());
956  auto transformed3 = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 0., p2.theta()), {p2.x(), p2.y(), 0.}}}(cov3);
957  match_cov3_to_cov2(3, 4, 2, transformed2, transformed3);
958  }
959 }
960 
961 /* ************************************************************************* */
962 TEST(Pose3, TransformCovariance6) {
963  // Use simple covariance matrices and transforms to create tests that can be
964  // validated with simple computations.
965  using namespace test_pose_adjoint_map;
966 
967  // rotate 90 around z axis and then 90 around y axis
968  {
969  auto cov = FullCovarianceFromSigmas<Pose3>((Vector6{} << 0.1, 0.2, 0.3, 0.5, 0.7, 1.1).finished());
970  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 90 * degree, 90 * degree), {0., 0., 0.}}}(cov);
971  // x from y, y from z, z from x
973  (Vector6{} << cov(1, 1), cov(2, 2), cov(0, 0), cov(4, 4), cov(5, 5), cov(3, 3)).finished(),
974  Vector6{transformed.diagonal()}));
975  // Both the x and z axes are pointing in the negative direction.
977  (Vector5{} << -cov(2, 1), cov(0, 1), cov(4, 1), -cov(5, 1), cov(3, 1)).finished(),
978  (Vector5{} << transformed(1, 0), transformed(2, 0), transformed(3, 0),
979  transformed(4, 0), transformed(5, 0)).finished()));
980  }
981 
982  // translate along the x axis with uncertainty in roty and rotz
983  {
984  auto cov = TwoVariableCovarianceFromSigmas<Pose3>(1, 2, 0.7, 0.3);
985  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(0., 0., 0.), {20., 0., 0.}}}(cov);
986  // The uncertainty in roty and rotz causes off-diagonal covariances
987  EXPECT(assert_equal(0.7 * 0.7 * 20., transformed(5, 1)));
988  EXPECT(assert_equal(0.7 * 0.7 * 20. * 20., transformed(5, 5)));
989  EXPECT(assert_equal(-0.3 * 0.3 * 20., transformed(4, 2)));
990  EXPECT(assert_equal(0.3 * 0.3 * 20. * 20., transformed(4, 4)));
991  EXPECT(assert_equal(-0.3 * 0.7 * 20., transformed(4, 1)));
992  EXPECT(assert_equal(0.3 * 0.7 * 20., transformed(5, 2)));
993  EXPECT(assert_equal(-0.3 * 0.7 * 20. * 20., transformed(5, 4)));
994  }
995 
996  // rotate around x axis and translate along the x axis with uncertainty in rotx
997  {
998  auto cov = SingleVariableCovarianceFromSigma<Pose3>(0, 0.1);
999  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(90 * degree, 0., 0.), {20., 0., 0.}}}(cov);
1000  // No change
1001  EXPECT(assert_equal(cov, transformed));
1002  }
1003 
1004  // rotate around x axis and translate along the x axis with uncertainty in roty
1005  {
1006  auto cov = SingleVariableCovarianceFromSigma<Pose3>(1, 0.1);
1007  auto transformed = TransformCovariance<Pose3>{{Rot3::RzRyRx(90 * degree, 0., 0.), {20., 0., 0.}}}(cov);
1008  // Uncertainty is spread to other dimensions.
1010  (Vector6{} << 0., 0., 0.1 * 0.1, 0., 0.1 * 0.1 * 20. * 20., 0.).finished(),
1011  Vector6{transformed.diagonal()}));
1012  }
1013 }
1014 
1015 /* ************************************************************************* */
1019 
1020  // Trivial example: start at origin and move to (1, 0, 0) while rotating pi/2
1021  // about z-axis.
1022  Pose3 start;
1023  Pose3 end(Rot3::Rz(M_PI_2), Point3(1, 0, 0));
1024  // This interpolation is easy to calculate by hand.
1025  double t = 0.5;
1026  Pose3 expected0(Rot3::Rz(M_PI_4), Point3(0.5, 0, 0));
1027  EXPECT(assert_equal(expected0, start.interpolateRt(end, t)));
1028 
1029  // Example from Peter Corke
1030  // https://robotacademy.net.au/lesson/interpolating-pose-in-3d/
1031  t = 0.0759; // corresponds to the 10th element when calling `ctraj` in
1032  // the video
1033  Pose3 O;
1034  Pose3 F(Rot3::Roll(0.6).compose(Rot3::Pitch(0.8)).compose(Rot3::Yaw(1.4)),
1035  Point3(1, 2, 3));
1036 
1037  // The expected answer matches the result presented in the video.
1038  Pose3 expected1(interpolate(O.rotation(), F.rotation(), t),
1039  interpolate(O.translation(), F.translation(), t));
1040  EXPECT(assert_equal(expected1, O.interpolateRt(F, t)));
1041 
1042  // Non-trivial interpolation, translation value taken from output.
1043  Pose3 expected2(interpolate(T2.rotation(), T3.rotation(), t),
1045  EXPECT(assert_equal(expected2, T2.interpolateRt(T3, t)));
1046 }
1047 
1048 /* ************************************************************************* */
1049 TEST(Pose3, Create) {
1050  Matrix63 actualH1, actualH2;
1051  Pose3 actual = Pose3::Create(R, P2, actualH1, actualH2);
1052  EXPECT(assert_equal(T, actual));
1053  boost::function<Pose3(Rot3,Point3)> create = boost::bind(Pose3::Create,_1,_2,boost::none,boost::none);
1054  EXPECT(assert_equal(numericalDerivative21<Pose3,Rot3,Point3>(create, R, P2), actualH1, 1e-9));
1055  EXPECT(assert_equal(numericalDerivative22<Pose3,Rot3,Point3>(create, R, P2), actualH2, 1e-9));
1056 }
1057 
1058 /* ************************************************************************* */
1060  Pose3 pose(Rot3::identity(), Point3(1, 2, 3));
1061 
1062  // Generate the expected output
1063  std::string expected = "R: [\n\t1, 0, 0;\n\t0, 1, 0;\n\t0, 0, 1\n]\nt: 1 2 3\n";
1064 
1065  EXPECT(assert_print_equal(expected, pose));
1066 }
1067 
1068 /* ************************************************************************* */
1069 int main() {
1070  TestResult tr;
1071  return TestRegistry::runAllTests(tr);
1072 }
1073 /* ************************************************************************* */
Provides additional testing facilities for common data structures.
Point3 l2(1, 1, 0)
#define CHECK(condition)
Definition: Test.h:109
Point2 q2
Definition: testPose2.cpp:753
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:360
Point3 transformFrom_(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:320
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:114
Scalar * y
Point2 q1
Definition: testPose2.cpp:753
Pose3 interpolateRt(const Pose3 &T, double t) const
Definition: Pose3.h:129
Matrix6 AdjointMap() const
Definition: Pose3.cpp:58
void adjoint(const MatrixType &m)
Definition: adjoint.cpp:67
static Point3 p3
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
Provides convenient mappings of common member functions for testing.
double c
Definition: testPose3.cpp:115
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
Pose3 xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4))
Vector3f p1
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
Definition: Pose3.h:154
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
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Q id(Eigen::AngleAxisd(0, Q_z_axis))
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
EIGEN_DEVICE_FUNC const LogReturnType log() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
Vector6 testDerivAdjoint(const Vector6 &xi, const Vector6 &v)
Definition: testPose3.cpp:834
Definition: Half.h:150
Key W(std::uint64_t j)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
Pose3 expected(expectedR, expectedT)
Rot2 theta
Pose3 xl2(Rot3::Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0))
#define GTSAM_CONCEPT_LIE_INST(T)
Definition: Lie.h:355
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:666
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HaTb=boost::none) const
Definition: Pose3.cpp:282
Pose3 Agrawal06iros(const Vector &xi)
Definition: testPose3.cpp:167
static void normalize(Signature::Row &row)
Definition: Signature.cpp:158
double w
Definition: testPose3.cpp:115
Point3 point(10, 0,-5)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
Point3 l3(2, 2, 0)
Pose3 xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0))
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
const double degree
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static const double tol
Definition: testPose3.cpp:41
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:298
T interpolate(const T &X, const T &Y, double t)
Definition: Lie.h:325
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:314
Class compose(const Class &g) const
Definition: Lie.h:47
Signature::Row F
Definition: Signature.cpp:53
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:50
Eigen::VectorXd Vector
Definition: Vector.h:38
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Key O(std::uint64_t j)
int main()
Definition: testPose3.cpp:1069
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Class expmap(const TangentVector &v) const
Definition: Lie.h:77
double range_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:596
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HwTb=boost::none) const
Definition: Pose3.cpp:289
#define EXPECT(condition)
Definition: Test.h:151
Point3 expectedT(0.29552, 0.0446635, 1)
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:334
Point3 l1(1, 0, 0)
Rot3 expectedR(c,-s, 0, s, c, 0, 0, 0, 1)
Vector6 testDerivAdjointTranspose(const Vector6 &xi, const Vector6 &v)
Definition: testPose3.cpp:852
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix wedge< Pose3 >(const Vector &xi)
Definition: Pose3.h:386
Support utilities for using AdjointMap for transforming Pose2 and Pose3 covariance matrices...
Point2 q3
Definition: testPose2.cpp:753
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
static const Matrix I
Definition: lago.cpp:35
#define ROT3_DEFAULT_COORDINATES_MODE
Definition: Rot3.h:43
TEST(Pose3, equals)
Definition: testPose3.cpp:44
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Pose3 xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0))
Point3 l4(1, 4,-4)
static const Pose3 T(R, P2)
Vector xi
Definition: testPose3.cpp:116
static const Point3 P2(3.5,-8.2, 4.2)
TangentVector logmap(const Class &g) const
Definition: Lie.h:83
traits
Definition: chartTesting.h:28
double a
Definition: testPose3.cpp:115
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:130
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
Matrix4 matrix() const
Definition: Pose3.cpp:274
Pose3 transformPoseFrom_(const Pose3 &wTa, const Pose3 &aTb)
Definition: testPose3.cpp:424
ADT create(const Signature &signature)
ofstream os("timeSchurFactors.csv")
Pose3 x1
Definition: testPose3.cpp:588
#define CHECK_CHART_DERIVATIVES(t1, t2)
Definition: testLie.h:85
float * p
Class between(const Class &g) const
Definition: Lie.h:51
static const Similarity3 T5(R, P, 10)
static Point3 p2
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(boost::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
double range_pose_proxy(const Pose3 &pose, const Pose3 &point)
Definition: testPose3.cpp:631
2D Pose
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
static const Rot3 R
Definition: testPose3.cpp:36
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
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Pose3 transformPoseTo_(const Pose3 &pose, const Pose3 &pose2)
Definition: testPose3.cpp:453
double s
Definition: testPose3.cpp:115
Point3 transform_to_(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:368
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
static const Point3 P(0.2, 0.7,-2)
Point2 t(10, 10)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:38


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:35