testPose2.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 
18 #include <gtsam/base/Testable.h>
20 #include <gtsam/base/lieProxies.h>
21 #include <gtsam/base/testLie.h>
22 #include <gtsam/geometry/Point2.h>
23 #include <gtsam/geometry/Pose2.h>
24 #include <gtsam/geometry/Rot2.h>
25 
26 #include <boost/assign/std/vector.hpp> // for operator +=
27 #include <boost/optional.hpp>
28 #include <cmath>
29 #include <iostream>
30 
31 using namespace boost::assign;
32 using namespace gtsam;
33 using namespace std;
34 
37 
38 //******************************************************************************
39 TEST(Pose2 , Concept) {
41  BOOST_CONCEPT_ASSERT((IsManifold<Pose2 >));
43 }
44 
45 /* ************************************************************************* */
46 TEST(Pose2, constructors) {
47  Point2 p(0,0);
48  Pose2 pose(0,p);
49  Pose2 origin;
50  assert_equal(pose,origin);
51  Pose2 t(M_PI/2.0+0.018, Point2(1.015, 2.01));
53 }
54 
55 /* ************************************************************************* */
56 TEST(Pose2, manifold) {
57  Pose2 t1(M_PI/2.0, Point2(1, 2));
58  Pose2 t2(M_PI/2.0+0.018, Point2(1.015, 2.01));
59  Pose2 origin;
60  Vector d12 = t1.localCoordinates(t2);
61  EXPECT(assert_equal(t2, t1.retract(d12)));
62  EXPECT(assert_equal(t2, t1*origin.retract(d12)));
63  Vector d21 = t2.localCoordinates(t1);
64  EXPECT(assert_equal(t1, t2.retract(d21)));
65  EXPECT(assert_equal(t1, t2*origin.retract(d21)));
66 }
67 
68 /* ************************************************************************* */
69 TEST(Pose2, retract) {
70  Pose2 pose(M_PI/2.0, Point2(1, 2));
71 #ifdef SLOW_BUT_CORRECT_EXPMAP
72  Pose2 expected(1.00811, 2.01528, 2.5608);
73 #else
74  Pose2 expected(M_PI/2.0+0.99, Point2(1.015, 2.01));
75 #endif
76  Pose2 actual = pose.retract(Vector3(0.01, -0.015, 0.99));
77  EXPECT(assert_equal(expected, actual, 1e-5));
78 }
79 
80 /* ************************************************************************* */
81 TEST(Pose2, expmap) {
82  Pose2 pose(M_PI/2.0, Point2(1, 2));
83  Pose2 expected(1.00811, 2.01528, 2.5608);
84  Pose2 actual = expmap_default<Pose2>(pose, Vector3(0.01, -0.015, 0.99));
85  EXPECT(assert_equal(expected, actual, 1e-5));
86 }
87 
88 /* ************************************************************************* */
89 TEST(Pose2, expmap2) {
90  Pose2 pose(M_PI/2.0, Point2(1, 2));
91  Pose2 expected(1.00811, 2.01528, 2.5608);
92  Pose2 actual = expmap_default<Pose2>(pose, Vector3(0.01, -0.015, 0.99));
93  EXPECT(assert_equal(expected, actual, 1e-5));
94 }
95 
96 /* ************************************************************************* */
97 TEST(Pose2, expmap3) {
98  // do an actual series exponential map
99  // see e.g. http://www.cis.upenn.edu/~cis610/cis610lie1.ps
100  Matrix A = (Matrix(3,3) <<
101  0.0, -0.99, 0.01,
102  0.99, 0.0, -0.015,
103  0.0, 0.0, 0.0).finished();
104  Matrix A2 = A*A/2.0, A3 = A2*A/3.0, A4=A3*A/4.0;
105  Matrix expected = I_3x3 + A + A2 + A3 + A4;
106 
107  Vector v = Vector3(0.01, -0.015, 0.99);
108  Pose2 pose = Pose2::Expmap(v);
109  Pose2 pose2(v);
110  EXPECT(assert_equal(pose, pose2));
111  Matrix actual = pose.matrix();
112  //EXPECT(assert_equal(expected, actual));
113 }
114 
115 /* ************************************************************************* */
116 TEST(Pose2, expmap0a) {
117  Pose2 expected(0.0101345, -0.0149092, 0.018);
118  Pose2 actual = Pose2::Expmap(Vector3(0.01, -0.015, 0.018));
119  EXPECT(assert_equal(expected, actual, 1e-5));
120 }
121 
122 /* ************************************************************************* */
123 TEST(Pose2, expmap0b) {
124  // a quarter turn
125  Pose2 expected(1.0, 1.0, M_PI/2);
126  Pose2 actual = Pose2::Expmap((Vector(3) << M_PI/2, 0.0, M_PI/2).finished());
127  EXPECT(assert_equal(expected, actual, 1e-5));
128 }
129 
130 /* ************************************************************************* */
131 TEST(Pose2, expmap0c) {
132  // a half turn
133  Pose2 expected(0.0, 2.0, M_PI);
134  Pose2 actual = Pose2::Expmap((Vector(3) << M_PI, 0.0, M_PI).finished());
135  EXPECT(assert_equal(expected, actual, 1e-5));
136 }
137 
138 /* ************************************************************************* */
139 TEST(Pose2, expmap0d) {
140  // a full turn
141  Pose2 expected(0, 0, 0);
142  Pose2 actual = Pose2::Expmap((Vector(3) << 2*M_PI, 0.0, 2*M_PI).finished());
143  EXPECT(assert_equal(expected, actual, 1e-5));
144 }
145 
146 /* ************************************************************************* */
147 // test case for screw motion in the plane
148 namespace screwPose2 {
149  double w=0.3;
150  Vector xi = (Vector(3) << 0.0, w, w).finished();
151  Rot2 expectedR = Rot2::fromAngle(w);
152  Point2 expectedT(-0.0446635, 0.29552);
153  Pose2 expected(expectedR, expectedT);
154 }
155 
156 TEST(Pose2, expmap_c)
157 {
161 }
162 
163 /* ************************************************************************* */
164 TEST(Pose2, expmap_c_full)
165 {
166  double w=0.3;
167  Vector xi = (Vector(3) << 0.0, w, w).finished();
168  Rot2 expectedR = Rot2::fromAngle(w);
169  Point2 expectedT(-0.0446635, 0.29552);
170  Pose2 expected(expectedR, expectedT);
171  EXPECT(assert_equal(expected, expm<Pose2>(xi),1e-6));
172  EXPECT(assert_equal(expected, Pose2::Expmap(xi),1e-6));
173  EXPECT(assert_equal(xi, Pose2::Logmap(expected),1e-6));
174 }
175 
176 /* ************************************************************************* */
177 // assert that T*exp(xi)*T^-1 is equal to exp(Ad_T(xi))
178 TEST(Pose2, Adjoint_full) {
179  Pose2 T(1, 2, 3);
181  Vector xiprime = T.Adjoint(screwPose2::xi);
182  EXPECT(assert_equal(expected, Pose2::Expmap(xiprime), 1e-6));
183 
184  Vector3 xi2(4, 5, 6);
185  Pose2 expected2 = T * Pose2::Expmap(xi2) * T.inverse();
186  Vector xiprime2 = T.Adjoint(xi2);
187  EXPECT(assert_equal(expected2, Pose2::Expmap(xiprime2), 1e-6));
188 }
189 
190 /* ************************************************************************* */
191 // assert that T*wedge(xi)*T^-1 is equal to wedge(Ad_T(xi))
192 TEST(Pose2, Adjoint_hat) {
193  Pose2 T(1, 2, 3);
194  auto hat = [](const Vector& xi) { return ::wedge<Pose2>(xi); };
195  Matrix3 expected = T.matrix() * hat(screwPose2::xi) * T.matrix().inverse();
196  Matrix3 xiprime = hat(T.Adjoint(screwPose2::xi));
197  EXPECT(assert_equal(expected, xiprime, 1e-6));
198 
199  Vector3 xi2(4, 5, 6);
200  Matrix3 expected2 = T.matrix() * hat(xi2) * T.matrix().inverse();
201  Matrix3 xiprime2 = hat(T.Adjoint(xi2));
202  EXPECT(assert_equal(expected2, xiprime2, 1e-6));
203 }
204 
205 /* ************************************************************************* */
206 TEST(Pose2, logmap) {
207  Pose2 pose0(M_PI/2.0, Point2(1, 2));
208  Pose2 pose(M_PI/2.0+0.018, Point2(1.015, 2.01));
209 #ifdef SLOW_BUT_CORRECT_EXPMAP
210  Vector3 expected(0.00986473, -0.0150896, 0.018);
211 #else
212  Vector3 expected(0.01, -0.015, 0.018);
213 #endif
214  Vector actual = pose0.localCoordinates(pose);
215  EXPECT(assert_equal(expected, actual, 1e-5));
216 }
217 
218 /* ************************************************************************* */
219 TEST(Pose2, logmap_full) {
220  Pose2 pose0(M_PI/2.0, Point2(1, 2));
221  Pose2 pose(M_PI/2.0+0.018, Point2(1.015, 2.01));
222  Vector expected = Vector3(0.00986473, -0.0150896, 0.018);
223  Vector actual = logmap_default<Pose2>(pose0, pose);
224  EXPECT(assert_equal(expected, actual, 1e-5));
225 }
226 
227 /* ************************************************************************* */
228 TEST( Pose2, ExpmapDerivative1) {
229  Matrix3 actualH;
230  Vector3 w(0.1, 0.27, -0.3);
231  Pose2::Expmap(w,actualH);
232  Matrix3 expectedH = numericalDerivative21<Pose2, Vector3,
233  OptionalJacobian<3, 3> >(&Pose2::Expmap, w, boost::none, 1e-2);
234  EXPECT(assert_equal(expectedH, actualH, 1e-5));
235 }
236 
237 /* ************************************************************************* */
238 TEST( Pose2, ExpmapDerivative2) {
239  Matrix3 actualH;
240  Vector3 w0(0.1, 0.27, 0.0); // alpha = 0
241  Pose2::Expmap(w0,actualH);
242  Matrix3 expectedH = numericalDerivative21<Pose2, Vector3,
243  OptionalJacobian<3, 3> >(&Pose2::Expmap, w0, boost::none, 1e-2);
244  EXPECT(assert_equal(expectedH, actualH, 1e-5));
245 }
246 
247 /* ************************************************************************* */
248 TEST( Pose2, LogmapDerivative1) {
249  Matrix3 actualH;
250  Vector3 w(0.1, 0.27, -0.3);
251  Pose2 p = Pose2::Expmap(w);
252  EXPECT(assert_equal(w, Pose2::Logmap(p,actualH), 1e-5));
253  Matrix3 expectedH = numericalDerivative21<Vector3, Pose2,
254  OptionalJacobian<3, 3> >(&Pose2::Logmap, p, boost::none, 1e-2);
255  EXPECT(assert_equal(expectedH, actualH, 1e-5));
256 }
257 
258 /* ************************************************************************* */
259 TEST( Pose2, LogmapDerivative2) {
260  Matrix3 actualH;
261  Vector3 w0(0.1, 0.27, 0.0); // alpha = 0
262  Pose2 p = Pose2::Expmap(w0);
263  EXPECT(assert_equal(w0, Pose2::Logmap(p,actualH), 1e-5));
264  Matrix3 expectedH = numericalDerivative21<Vector3, Pose2,
265  OptionalJacobian<3, 3> >(&Pose2::Logmap, p, boost::none, 1e-2);
266  EXPECT(assert_equal(expectedH, actualH, 1e-5));
267 }
268 
269 /* ************************************************************************* */
270 static Point2 transformTo_(const Pose2& pose, const Point2& point) {
271  return pose.transformTo(point);
272 }
273 
275  Pose2 pose(M_PI / 2.0, Point2(1, 2)); // robot at (1,2) looking towards y
276  Point2 point(-1, 4); // landmark at (-1,4)
277 
278  // expected
279  Point2 expected(2, 2);
280  Matrix expectedH1 =
281  (Matrix(2, 3) << -1.0, 0.0, 2.0, 0.0, -1.0, -2.0).finished();
282  Matrix expectedH2 = (Matrix(2, 2) << 0.0, 1.0, -1.0, 0.0).finished();
283 
284  // actual
285  Matrix actualH1, actualH2;
286  Point2 actual = pose.transformTo(point, actualH1, actualH2);
287  EXPECT(assert_equal(expected, actual));
288 
289  EXPECT(assert_equal(expectedH1, actualH1));
290  Matrix numericalH1 = numericalDerivative21(transformTo_, pose, point);
291  EXPECT(assert_equal(numericalH1, actualH1));
292 
293  EXPECT(assert_equal(expectedH2, actualH2));
294  Matrix numericalH2 = numericalDerivative22(transformTo_, pose, point);
295  EXPECT(assert_equal(numericalH2, actualH2));
296 }
297 
298 /* ************************************************************************* */
299 static Point2 transformFrom_(const Pose2& pose, const Point2& point) {
300  return pose.transformFrom(point);
301 }
302 
304  Pose2 pose(1., 0., M_PI / 2.0);
305  Point2 pt(2., 1.);
306  Matrix H1, H2;
307  Point2 actual = pose.transformFrom(pt, H1, H2);
308 
309  Point2 expected(0., 2.);
310  EXPECT(assert_equal(expected, actual));
311 
312  Matrix H1_expected = (Matrix(2, 3) << 0., -1., -2., 1., 0., -1.).finished();
313  Matrix H2_expected = (Matrix(2, 2) << 0., -1., 1., 0.).finished();
314 
315  Matrix numericalH1 = numericalDerivative21(transformFrom_, pose, pt);
316  EXPECT(assert_equal(H1_expected, H1));
317  EXPECT(assert_equal(H1_expected, numericalH1));
318 
319  Matrix numericalH2 = numericalDerivative22(transformFrom_, pose, pt);
320  EXPECT(assert_equal(H2_expected, H2));
321  EXPECT(assert_equal(H2_expected, numericalH2));
322 }
323 
324 /* ************************************************************************* */
325 TEST(Pose2, compose_a)
326 {
327  Pose2 pose1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)));
328  Pose2 pose2(M_PI/2.0, Point2(0.0, 2.0));
329 
330  Matrix actualDcompose1;
331  Matrix actualDcompose2;
332  Pose2 actual = pose1.compose(pose2, actualDcompose1, actualDcompose2);
333 
334  Pose2 expected(3.0*M_PI/4.0, Point2(-sqrt(0.5), 3.0*sqrt(0.5)));
335  EXPECT(assert_equal(expected, actual));
336 
337  Matrix expectedH1 = (Matrix(3,3) <<
338  0.0, 1.0, 0.0,
339  -1.0, 0.0, 2.0,
340  0.0, 0.0, 1.0
341  ).finished();
342  Matrix expectedH2 = I_3x3;
343  Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
344  Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
345  EXPECT(assert_equal(expectedH1,actualDcompose1));
346  EXPECT(assert_equal(numericalH1,actualDcompose1));
347  EXPECT(assert_equal(expectedH2,actualDcompose2));
348  EXPECT(assert_equal(numericalH2,actualDcompose2));
349 
350  Point2 point(sqrt(0.5), 3.0*sqrt(0.5));
351  Point2 expected_point(-1.0, -1.0);
352  Point2 actual_point1 = (pose1 * pose2).transformTo(point);
353  Point2 actual_point2 = pose2.transformTo(pose1.transformTo(point));
354  EXPECT(assert_equal(expected_point, actual_point1));
355  EXPECT(assert_equal(expected_point, actual_point2));
356 }
357 
358 /* ************************************************************************* */
359 TEST(Pose2, compose_b)
360 {
361  Pose2 pose1(Rot2::fromAngle(M_PI/10.0), Point2(.75, .5));
362  Pose2 pose2(Rot2::fromAngle(M_PI/4.0-M_PI/10.0), Point2(0.701289620636, 1.34933052585));
363 
364  Pose2 pose_expected(Rot2::fromAngle(M_PI/4.0), Point2(1.0, 2.0));
365 
366  Pose2 pose_actual_op = pose1 * pose2;
367  Matrix actualDcompose1, actualDcompose2;
368  Pose2 pose_actual_fcn = pose1.compose(pose2, actualDcompose1, actualDcompose2);
369 
370  Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
371  Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
372  EXPECT(assert_equal(numericalH1,actualDcompose1,1e-5));
373  EXPECT(assert_equal(numericalH2,actualDcompose2));
374 
375  EXPECT(assert_equal(pose_expected, pose_actual_op));
376  EXPECT(assert_equal(pose_expected, pose_actual_fcn));
377 }
378 
379 /* ************************************************************************* */
380 TEST(Pose2, compose_c)
381 {
382  Pose2 pose1(Rot2::fromAngle(M_PI/4.0), Point2(1.0, 1.0));
383  Pose2 pose2(Rot2::fromAngle(M_PI/4.0), Point2(sqrt(.5), sqrt(.5)));
384 
385  Pose2 pose_expected(Rot2::fromAngle(M_PI/2.0), Point2(1.0, 2.0));
386 
387  Pose2 pose_actual_op = pose1 * pose2;
388  Matrix actualDcompose1, actualDcompose2;
389  Pose2 pose_actual_fcn = pose1.compose(pose2, actualDcompose1, actualDcompose2);
390 
391  Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
392  Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(testing::compose, pose1, pose2);
393  EXPECT(assert_equal(numericalH1,actualDcompose1,1e-5));
394  EXPECT(assert_equal(numericalH2,actualDcompose2));
395 
396  EXPECT(assert_equal(pose_expected, pose_actual_op));
397  EXPECT(assert_equal(pose_expected, pose_actual_fcn));
398 }
399 
400 /* ************************************************************************* */
402 {
403  Point2 origin(0,0), t(1,2);
404  Pose2 gTl(M_PI/2.0, t); // robot at (1,2) looking towards y
405 
406  Pose2 identity, lTg = gTl.inverse();
407  EXPECT(assert_equal(identity,lTg.compose(gTl)));
408  EXPECT(assert_equal(identity,gTl.compose(lTg)));
409 
410  Point2 l(4,5), g(-4,6);
411  EXPECT(assert_equal(g,gTl*l));
412  EXPECT(assert_equal(l,lTg*g));
413 
414  // Check derivative
415  Matrix numericalH = numericalDerivative11<Pose2,Pose2>(testing::inverse, lTg);
416  Matrix actualDinverse;
417  lTg.inverse(actualDinverse);
418  EXPECT(assert_equal(numericalH,actualDinverse));
419 }
420 
421 namespace {
422  /* ************************************************************************* */
423  Vector homogeneous(const Point2& p) {
424  return (Vector(3) << p.x(), p.y(), 1.0).finished();
425  }
426 
427  /* ************************************************************************* */
428  Matrix matrix(const Pose2& gTl) {
429  Matrix gRl = gTl.r().matrix();
430  Point2 gt = gTl.t();
431  return (Matrix(3, 3) <<
432  gRl(0, 0), gRl(0, 1), gt.x(),
433  gRl(1, 0), gRl(1, 1), gt.y(),
434  0.0, 0.0, 1.0).finished();
435  }
436 }
437 
438 /* ************************************************************************* */
440 {
441  Point2 origin(0,0), t(1,2);
442  Pose2 gTl(M_PI/2.0, t); // robot at (1,2) looking towards y
443  Matrix gMl = matrix(gTl);
444  EXPECT(assert_equal((Matrix(3,3) <<
445  0.0, -1.0, 1.0,
446  1.0, 0.0, 2.0,
447  0.0, 0.0, 1.0).finished(),
448  gMl));
449  Rot2 gR1 = gTl.r();
451  Point2 x_axis(1,0), y_axis(0,1);
452  EXPECT(assert_equal((Matrix(2,2) <<
453  0.0, -1.0,
454  1.0, 0.0).finished(),
455  gR1.matrix()));
456  EXPECT(assert_equal(Point2(0,1),gR1*x_axis));
457  EXPECT(assert_equal(Point2(-1,0),gR1*y_axis));
458  EXPECT(assert_equal(homogeneous(Point2(1+0,2+1)),gMl*homogeneous(x_axis)));
459  EXPECT(assert_equal(homogeneous(Point2(1-1,2+0)),gMl*homogeneous(y_axis)));
460 
461  // check inverse pose
462  Matrix lMg = matrix(gTl.inverse());
463  EXPECT(assert_equal((Matrix(3,3) <<
464  0.0, 1.0,-2.0,
465  -1.0, 0.0, 1.0,
466  0.0, 0.0, 1.0).finished(),
467  lMg));
468 }
469 
470 /* ************************************************************************* */
471 TEST( Pose2, compose_matrix )
472 {
473  Pose2 gT1(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y
474  Pose2 _1T2(M_PI, Point2(-1,4)); // local robot at (-1,4) looking at negative x
475  Matrix gM1(matrix(gT1)),_1M2(matrix(_1T2));
476  EXPECT(assert_equal(gM1*_1M2,matrix(gT1.compose(_1T2)))); // RIGHT DOES NOT
477 }
478 
479 /* ************************************************************************* */
481 {
482  // <
483  //
484  // ^
485  //
486  // *--0--*--*
487  Pose2 gT1(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y
488  Pose2 gT2(M_PI, Point2(-1,4)); // robot at (-1,4) looking at negative x
489 
490  Matrix actualH1,actualH2;
491  Pose2 expected(M_PI/2.0, Point2(2,2));
492  Pose2 actual1 = gT1.between(gT2);
493  Pose2 actual2 = gT1.between(gT2,actualH1,actualH2);
494  EXPECT(assert_equal(expected,actual1));
495  EXPECT(assert_equal(expected,actual2));
496 
497  Matrix expectedH1 = (Matrix(3,3) <<
498  0.0,-1.0,-2.0,
499  1.0, 0.0,-2.0,
500  0.0, 0.0,-1.0
501  ).finished();
502  Matrix numericalH1 = numericalDerivative21<Pose2,Pose2,Pose2>(testing::between, gT1, gT2);
503  EXPECT(assert_equal(expectedH1,actualH1));
504  EXPECT(assert_equal(numericalH1,actualH1));
505  // Assert H1 = -AdjointMap(between(p2,p1)) as in doc/math.lyx
506  EXPECT(assert_equal(-gT2.between(gT1).AdjointMap(),actualH1));
507 
508  Matrix expectedH2 = (Matrix(3,3) <<
509  1.0, 0.0, 0.0,
510  0.0, 1.0, 0.0,
511  0.0, 0.0, 1.0
512  ).finished();
513  Matrix numericalH2 = numericalDerivative22<Pose2,Pose2,Pose2>(testing::between, gT1, gT2);
514  EXPECT(assert_equal(expectedH2,actualH2));
515  EXPECT(assert_equal(numericalH2,actualH2));
516 
517 }
518 
519 /* ************************************************************************* */
520 // reverse situation for extra test
521 TEST( Pose2, between2 )
522 {
523  Pose2 p2(M_PI/2.0, Point2(1,2)); // robot at (1,2) looking towards y
524  Pose2 p1(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x
525 
526  Matrix actualH1,actualH2;
527  p1.between(p2,actualH1,actualH2);
528  Matrix numericalH1 = numericalDerivative21<Pose2,Pose2,Pose2>(testing::between, p1, p2);
529  EXPECT(assert_equal(numericalH1,actualH1));
530  Matrix numericalH2 = numericalDerivative22<Pose2,Pose2,Pose2>(testing::between, p1, p2);
531  EXPECT(assert_equal(numericalH2,actualH2));
532 }
533 
534 /* ************************************************************************* */
535 // arbitrary, non perpendicular angles to be extra safe
536 TEST( Pose2, between3 )
537 {
538  Pose2 p2(M_PI/3.0, Point2(1,2));
539  Pose2 p1(M_PI/6.0, Point2(-1,4));
540 
541  Matrix actualH1,actualH2;
542  p1.between(p2,actualH1,actualH2);
543  Matrix numericalH1 = numericalDerivative21<Pose2,Pose2,Pose2>(testing::between, p1, p2);
544  EXPECT(assert_equal(numericalH1,actualH1));
545  Matrix numericalH2 = numericalDerivative22<Pose2,Pose2,Pose2>(testing::between, p1, p2);
546  EXPECT(assert_equal(numericalH2,actualH2));
547 }
548 
549 /* ************************************************************************* */
550 TEST( Pose2, round_trip )
551 {
552  Pose2 p1(1.23, 2.30, 0.2);
553  Pose2 odo(0.53, 0.39, 0.15);
554  Pose2 p2 = p1.compose(odo);
555  EXPECT(assert_equal(odo, p1.between(p2)));
556 }
557 
558 namespace {
559  /* ************************************************************************* */
560  // some shared test values
561  Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI/4.0);
562  Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3);
563 
564  /* ************************************************************************* */
565  Rot2 bearing_proxy(const Pose2& pose, const Point2& pt) {
566  return pose.bearing(pt);
567  }
568 }
569 
570 TEST( Pose2, bearing )
571 {
572  Matrix expectedH1, actualH1, expectedH2, actualH2;
573 
574  // establish bearing is indeed zero
576 
577  // establish bearing is indeed 45 degrees
578  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),x1.bearing(l2)));
579 
580  // establish bearing is indeed 45 degrees even if shifted
581  Rot2 actual23 = x2.bearing(l3, actualH1, actualH2);
582  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual23));
583 
584  // Check numerical derivatives
585  expectedH1 = numericalDerivative21(bearing_proxy, x2, l3);
586  EXPECT(assert_equal(expectedH1,actualH1));
587  expectedH2 = numericalDerivative22(bearing_proxy, x2, l3);
588  EXPECT(assert_equal(expectedH2,actualH2));
589 
590  // establish bearing is indeed 45 degrees even if rotated
591  Rot2 actual34 = x3.bearing(l4, actualH1, actualH2);
592  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual34));
593 
594  // Check numerical derivatives
595  expectedH1 = numericalDerivative21(bearing_proxy, x3, l4);
596  expectedH2 = numericalDerivative22(bearing_proxy, x3, l4);
597  EXPECT(assert_equal(expectedH1,actualH1));
598  EXPECT(assert_equal(expectedH2,actualH2));
599 }
600 
601 /* ************************************************************************* */
602 namespace {
603  Rot2 bearing_pose_proxy(const Pose2& pose, const Pose2& pt) {
604  return pose.bearing(pt);
605  }
606 }
607 
608 TEST( Pose2, bearing_pose )
609 {
610  Pose2 xl1(1, 0, M_PI/2.0), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI/2.0), xl4(1, 3, 0);
611 
612  Matrix expectedH1, actualH1, expectedH2, actualH2;
613 
614  // establish bearing is indeed zero
616 
617  // establish bearing is indeed 45 degrees
618  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),x1.bearing(xl2)));
619 
620  // establish bearing is indeed 45 degrees even if shifted
621  Rot2 actual23 = x2.bearing(xl3, actualH1, actualH2);
622  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual23));
623 
624  // Check numerical derivatives
625  expectedH1 = numericalDerivative21(bearing_pose_proxy, x2, xl3);
626  expectedH2 = numericalDerivative22(bearing_pose_proxy, x2, xl3);
627  EXPECT(assert_equal(expectedH1,actualH1));
628  EXPECT(assert_equal(expectedH2,actualH2));
629 
630  // establish bearing is indeed 45 degrees even if rotated
631  Rot2 actual34 = x3.bearing(xl4, actualH1, actualH2);
632  EXPECT(assert_equal(Rot2::fromAngle(M_PI/4.0),actual34));
633 
634  // Check numerical derivatives
635  expectedH1 = numericalDerivative21(bearing_pose_proxy, x3, xl4);
636  expectedH2 = numericalDerivative22(bearing_pose_proxy, x3, xl4);
637  EXPECT(assert_equal(expectedH1,actualH1));
638  EXPECT(assert_equal(expectedH2,actualH2));
639 }
640 
641 /* ************************************************************************* */
642 namespace {
643  double range_proxy(const Pose2& pose, const Point2& point) {
644  return pose.range(point);
645  }
646 }
647 TEST( Pose2, range )
648 {
649  Matrix expectedH1, actualH1, expectedH2, actualH2;
650 
651  // establish range is indeed zero
653 
654  // establish range is indeed 45 degrees
655  EXPECT_DOUBLES_EQUAL(sqrt(2.0),x1.range(l2),1e-9);
656 
657  // Another pair
658  double actual23 = x2.range(l3, actualH1, actualH2);
659  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
660 
661  // Check numerical derivatives
662  expectedH1 = numericalDerivative21(range_proxy, x2, l3);
663  expectedH2 = numericalDerivative22(range_proxy, x2, l3);
664  EXPECT(assert_equal(expectedH1,actualH1));
665  EXPECT(assert_equal(expectedH2,actualH2));
666 
667  // Another test
668  double actual34 = x3.range(l4, actualH1, actualH2);
669  EXPECT_DOUBLES_EQUAL(2,actual34,1e-9);
670 
671  // Check numerical derivatives
672  expectedH1 = numericalDerivative21(range_proxy, x3, l4);
673  expectedH2 = numericalDerivative22(range_proxy, x3, l4);
674  EXPECT(assert_equal(expectedH1,actualH1));
675  EXPECT(assert_equal(expectedH2,actualH2));
676 }
677 
678 /* ************************************************************************* */
679 namespace {
680  double range_pose_proxy(const Pose2& pose, const Pose2& point) {
681  return pose.range(point);
682  }
683 }
684 TEST( Pose2, range_pose )
685 {
686  Pose2 xl1(1, 0, M_PI/2.0), xl2(1, 1, M_PI), xl3(2.0, 2.0,-M_PI/2.0), xl4(1, 3, 0);
687 
688  Matrix expectedH1, actualH1, expectedH2, actualH2;
689 
690  // establish range is indeed zero
692 
693  // establish range is indeed 45 degrees
695 
696  // Another pair
697  double actual23 = x2.range(xl3, actualH1, actualH2);
698  EXPECT_DOUBLES_EQUAL(sqrt(2.0),actual23,1e-9);
699 
700  // Check numerical derivatives
703  EXPECT(assert_equal(expectedH1,actualH1));
704  EXPECT(assert_equal(expectedH2,actualH2));
705 
706  // Another test
707  double actual34 = x3.range(xl4, actualH1, actualH2);
708  EXPECT_DOUBLES_EQUAL(2,actual34,1e-9);
709 
710  // Check numerical derivatives
711  expectedH1 = numericalDerivative21(range_pose_proxy, x3, xl4);
712  expectedH2 = numericalDerivative22(range_pose_proxy, x3, xl4);
713  EXPECT(assert_equal(expectedH1,actualH1));
714  EXPECT(assert_equal(expectedH2,actualH2));
715 }
716 
717 /* ************************************************************************* */
718 
719 TEST(Pose2, align_1) {
720  Pose2 expected(Rot2::fromAngle(0), Point2(10,10));
721 
722  vector<Point2Pair> correspondences;
723  Point2Pair pq1(make_pair(Point2(0,0), Point2(10,10)));
724  Point2Pair pq2(make_pair(Point2(20,10), Point2(30,20)));
725  correspondences += pq1, pq2;
726 
727  boost::optional<Pose2> actual = align(correspondences);
728  EXPECT(assert_equal(expected, *actual));
729 }
730 
731 TEST(Pose2, align_2) {
732  Point2 t(20,10);
733  Rot2 R = Rot2::fromAngle(M_PI/2.0);
734  Pose2 expected(R, t);
735 
736  vector<Point2Pair> correspondences;
737  Point2 p1(0,0), p2(10,0);
738  Point2 q1 = expected.transformFrom(p1), q2 = expected.transformFrom(p2);
739  EXPECT(assert_equal(Point2(20,10),q1));
740  EXPECT(assert_equal(Point2(20,20),q2));
741  Point2Pair pq1(make_pair(p1, q1));
742  Point2Pair pq2(make_pair(p2, q2));
743  correspondences += pq1, pq2;
744 
745  boost::optional<Pose2> actual = align(correspondences);
746  EXPECT(assert_equal(expected, *actual));
747 }
748 
749 namespace align_3 {
750  Point2 t(10,10);
751  Pose2 expected(Rot2::fromAngle(2*M_PI/3), t);
752  Point2 p1(0,0), p2(10,0), p3(10,10);
753  Point2 q1 = expected.transformFrom(p1), q2 = expected.transformFrom(p2), q3 = expected.transformFrom(p3);
754 }
755 
757  using namespace align_3;
758 
759  vector<Point2Pair> correspondences;
760  Point2Pair pq1(make_pair(p1, q1));
761  Point2Pair pq2(make_pair(p2, q2));
762  Point2Pair pq3(make_pair(p3, q3));
763  correspondences += pq1, pq2, pq3;
764 
765  boost::optional<Pose2> actual = align(correspondences);
766  EXPECT(assert_equal(expected, *actual));
767 }
768 
769 namespace {
770  /* ************************************************************************* */
771  // Prototype code to align two triangles using a rigid transform
772  /* ************************************************************************* */
773  struct Triangle { size_t i_,j_,k_;};
774 
775  boost::optional<Pose2> align2(const Point2Vector& ps, const Point2Vector& qs,
776  const pair<Triangle, Triangle>& trianglePair) {
777  const Triangle& t1 = trianglePair.first, t2 = trianglePair.second;
778  vector<Point2Pair> correspondences;
779  correspondences += make_pair(ps[t1.i_],qs[t2.i_]), make_pair(ps[t1.j_],qs[t2.j_]), make_pair(ps[t1.k_],qs[t2.k_]);
780  return align(correspondences);
781  }
782 }
783 
784 TEST(Pose2, align_4) {
785  using namespace align_3;
786 
787  Point2Vector ps,qs;
788  ps += p1, p2, p3;
789  qs += q3, q1, q2; // note in 3,1,2 order !
790 
791  Triangle t1; t1.i_=0; t1.j_=1; t1.k_=2;
792  Triangle t2; t2.i_=1; t2.j_=2; t2.k_=0;
793 
794  boost::optional<Pose2> actual = align2(ps, qs, make_pair(t1,t2));
795  EXPECT(assert_equal(expected, *actual));
796 }
797 
798 //******************************************************************************
799 Pose2 T1(M_PI / 4.0, Point2(sqrt(0.5), sqrt(0.5)));
800 Pose2 T2(M_PI / 2.0, Point2(0.0, 2.0));
801 
802 //******************************************************************************
803 TEST(Pose2 , Invariants) {
804  Pose2 id;
805 
806  EXPECT(check_group_invariants(id,id));
807  EXPECT(check_group_invariants(id,T1));
808  EXPECT(check_group_invariants(T2,id));
809  EXPECT(check_group_invariants(T2,T1));
810 
811  EXPECT(check_manifold_invariants(id,id));
812  EXPECT(check_manifold_invariants(id,T1));
813  EXPECT(check_manifold_invariants(T2,id));
814  EXPECT(check_manifold_invariants(T2,T1));
815 
816 }
817 
818 //******************************************************************************
819 TEST(Pose2 , LieGroupDerivatives) {
820  Pose2 id;
821 
826 
827 }
828 
829 //******************************************************************************
830 TEST(Pose2 , ChartDerivatives) {
831  Pose2 id;
832 
837 }
838 
839 //******************************************************************************
840 #include "testPoseAdjointMap.h"
841 
842 TEST(Pose2 , TransformCovariance3) {
843  // Use simple covariance matrices and transforms to create tests that can be
844  // validated with simple computations.
845  using namespace test_pose_adjoint_map;
846 
847  // rotate
848  {
849  auto cov = FullCovarianceFromSigmas<Pose2>({0.1, 0.3, 0.7});
850  auto transformed = TransformCovariance<Pose2>{{0., 0., 90 * degree}}(cov);
851  // interchange x and y axes
853  Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
854  Vector3{transformed.diagonal()}));
856  Vector3{-cov(1, 0), -cov(2, 1), cov(2, 0)},
857  Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
858  }
859 
860  // translate along x with uncertainty in x
861  {
862  auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
863  auto transformed = TransformCovariance<Pose2>{{20., 0., 0.}}(cov);
864  // No change
865  EXPECT(assert_equal(cov, transformed));
866  }
867 
868  // translate along x with uncertainty in y
869  {
870  auto cov = SingleVariableCovarianceFromSigma<Pose2>(1, 0.1);
871  auto transformed = TransformCovariance<Pose2>{{20., 0., 0.}}(cov);
872  // No change
873  EXPECT(assert_equal(cov, transformed));
874  }
875 
876  // translate along x with uncertainty in theta
877  {
878  auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
879  auto transformed = TransformCovariance<Pose2>{{20., 0., 0.}}(cov);
881  Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
882  Vector3{transformed.diagonal()}));
884  Vector3{0., 0., -0.1 * 0.1 * 20.},
885  Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
886  }
887 
888  // rotate and translate along x with uncertainty in x
889  {
890  auto cov = SingleVariableCovarianceFromSigma<Pose2>(0, 0.1);
891  auto transformed = TransformCovariance<Pose2>{{20., 0., 90 * degree}}(cov);
892  // interchange x and y axes
894  Vector3{cov(1, 1), cov(0, 0), cov(2, 2)},
895  Vector3{transformed.diagonal()}));
897  Vector3{Z_3x1},
898  Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
899  }
900 
901  // rotate and translate along x with uncertainty in theta
902  {
903  auto cov = SingleVariableCovarianceFromSigma<Pose2>(2, 0.1);
904  auto transformed = TransformCovariance<Pose2>{{20., 0., 90 * degree}}(cov);
906  Vector3{0., 0.1 * 0.1 * 20. * 20., 0.1 * 0.1},
907  Vector3{transformed.diagonal()}));
909  Vector3{0., 0., -0.1 * 0.1 * 20.},
910  Vector3{transformed(1, 0), transformed(2, 0), transformed(2, 1)}));
911  }
912 }
913 
914 /* ************************************************************************* */
916  Pose2 pose(Rot2::identity(), Point2(1, 2));
917 
918  // Generate the expected output
919  string s = "Planar Pose";
920  string expected_stdout = "(1, 2, 0)";
921  string expected1 = expected_stdout + "\n";
922  string expected2 = s + " " + expected1;
923 
924  EXPECT(assert_stdout_equal(expected_stdout, pose));
925 
926  EXPECT(assert_print_equal(expected1, pose));
927  EXPECT(assert_print_equal(expected2, pose, s));
928 }
929 
930 /* ************************************************************************* */
931 int main() {
932  TestResult tr;
933  return TestRegistry::runAllTests(tr);
934 }
935 /* ************************************************************************* */
936 
bool assert_stdout_equal(const std::string &expected, const V &actual)
Provides additional testing facilities for common data structures.
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
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Point2 q1
Definition: testPose2.cpp:753
Concept check for values that can be used in unit tests.
Provides convenient mappings of common member functions for testing.
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
void homogeneous(void)
Pose3 xl4(Rot3::Ypr(0.0, 0.0, 1.0), Point3(1, 4,-4))
GTSAM_EXPORT Matrix3 matrix() const
Definition: Pose2.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 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="")
std::pair< Point2, Point2 > Point2Pair
Definition: Point2.h:38
const Point2 & t() const
translation
Definition: Pose2.h:224
Q id(Eigen::AngleAxisd(0, Q_z_axis))
Point2 odo(const Point2 &x1, const Point2 &x2)
odometry between two poses
Definition: simulated2D.h:98
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
int main()
Definition: testPose2.cpp:931
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
Rot2 R(Rot2::fromAngle(0.1))
gtsam::Key l2
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Definition: Half.h:150
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
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)
static const Point3 pt(1.0, 2.0, 3.0)
const Rot2 & r() const
rotation
Definition: Pose2.h:227
Pose2 expected(Rot2::fromAngle(2 *M_PI/3), t)
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
void g(const string &key, int i)
Definition: testBTree.cpp:43
int RealScalar int RealScalar int RealScalar RealScalar * ps
Unit3 bearing_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:666
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Definition: Pose2.cpp:228
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
Point2 expectedT(-0.0446635, 0.29552)
Point3 point(10, 0,-5)
#define CHECK_LIE_GROUP_DERIVATIVES(t1, t2)
Definition: testLie.h:82
Pose3 xl3(Rot3::Ypr(1.0, 0.0, 0.0), Point3(2, 2, 0))
const double degree
static const Line3 l(Rot3(), 1, 1)
Class compose(const Class &g) const
Definition: Lie.h:47
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
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)
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
Definition: Pose2.h:137
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Definition: Point2.h:42
double range_proxy(const Pose3 &pose, const Point3 &point)
Definition: testPose3.cpp:596
Point2 p2(10, 0)
#define EXPECT(condition)
Definition: Test.h:151
Matrix wedge< Pose2 >(const Vector &xi)
Definition: Pose2.h:313
Eigen::Triplet< double > T
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:334
Matrix2 matrix() const
Definition: Rot2.cpp:89
static const Symbol l3('l', 3)
static Point2 transformFrom_(const Pose2 &pose, const Point2 &point)
Definition: testPose2.cpp:299
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Support utilities for using AdjointMap for transforming Pose2 and Pose3 covariance matrices...
Point2 q3
Definition: testPose2.cpp:753
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Pose3 xl1(Rot3::Ypr(0.0, 0.0, 0.0), Point3(1, 0, 0))
Point3 l4(1, 4,-4)
Vector xi
Definition: testPose2.cpp:150
gtsam::Key l1
static Pose3 pose0
traits
Definition: chartTesting.h:28
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Definition: Pose2.cpp:314
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
static Point2 transformTo_(const Pose2 &pose, const Point2 &point)
Definition: testPose2.cpp:270
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Definition: Pose2.cpp:218
Rot2 expectedR
Definition: testPose2.cpp:151
TEST(Pose2, Concept)
Definition: testPose2.cpp:39
GTSAM_EXPORT Matrix3 AdjointMap() const
Definition: Pose2.cpp:126
Point2 p1(0, 0)
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
Point2 p3(10, 10)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
static const Pose3 pose2
GTSAM_EXPORT Pose2 inverse() const
inverse
Definition: Pose2.cpp:201
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)
2D Point
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1=boost::none, OptionalJacobian< 1, 2 > H2=boost::none) const
Definition: Pose2.cpp:253
2D rotation
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Definition: Testable.h:174
Point2 t(10, 10)
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose=boost::none, OptionalJacobian< 2, 2 > Dpoint=boost::none) const
Definition: Pose2.cpp:207
Pose2 expected(expectedR, expectedT)
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:135
double w
Definition: testPose2.cpp:149


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