| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  |  * @file testTupleValues.cpp | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  |  * @author Richard Roberts | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | #include <stdexcept>
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-31 04:54:12 +08:00
										 |  |  | #include <gtsam/base/TestableAssertions.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point3.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/base/Vector.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/nonlinear/Key.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | #include <gtsam/nonlinear/TupleValues-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | static const double tol = 1e-5; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | typedef TypedSymbol<Pose2, 'x'> PoseKey; | 
					
						
							|  |  |  | typedef TypedSymbol<Point2, 'l'> PointKey; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | typedef LieValues<PoseKey> PoseValues; | 
					
						
							|  |  |  | typedef LieValues<PointKey> PointValues; | 
					
						
							|  |  |  | typedef TupleValues2<PoseValues, PointValues> Values; | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, constructors ) | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  | 	Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Values::Values1 cfg1; | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | 	cfg1.insert(PoseKey(1), x1); | 
					
						
							|  |  |  | 	cfg1.insert(PoseKey(2), x2); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Values::Values2 cfg2; | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | 	cfg2.insert(PointKey(1), l1); | 
					
						
							|  |  |  | 	cfg2.insert(PointKey(2), l2); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	Values actual(cfg1, cfg2), expected; | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | 	expected.insert(PoseKey(1), x1); | 
					
						
							|  |  |  | 	expected.insert(PoseKey(2), x2); | 
					
						
							|  |  |  | 	expected.insert(PointKey(1), l1); | 
					
						
							|  |  |  | 	expected.insert(PointKey(2), l2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, insert_equals1 ) | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-06-08 02:00:43 +08:00
										 |  |  | 	Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  | 	Point2 l1(4,5), l2(9,10); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values expected; | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  |   expected.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   expected.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   expected.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   expected.insert(PointKey(2), l2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values actual; | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  |   actual.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   actual.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   actual.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   actual.insert(PointKey(2), l2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   CHECK(assert_equal(expected,actual)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-15 05:15:45 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, insert_equals2 ) | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  |   Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config1.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   config1.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   config1.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   config1.insert(PointKey(2), l2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config2; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config2.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   config2.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   config2.insert(PointKey(1), l1); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   CHECK(!config1.equals(config2)); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config2.insert(2, Point2(9,11)); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   CHECK(!config1.equals(config2)); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-31 00:19:52 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, insert_duplicate ) | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  |   Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config1.insert(1, x1); // 3
 | 
					
						
							|  |  |  |   config1.insert(2, x2); // 6
 | 
					
						
							|  |  |  |   config1.insert(1, l1); // 8
 | 
					
						
							|  |  |  |   config1.insert(2, l2); // 10
 | 
					
						
							|  |  |  |   config1.insert(2, l1); // still 10 !!!!
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   CHECK(assert_equal(l2, config1[PointKey(2)])); | 
					
						
							|  |  |  |   LONGS_EQUAL(4,config1.size()); | 
					
						
							|  |  |  |   LONGS_EQUAL(10,config1.dim()); | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, size_dim ) | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  |   Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config1.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   config1.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   config1.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   config1.insert(PointKey(2), l2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  |   EXPECT(config1.size() == 4); | 
					
						
							|  |  |  |   EXPECT(config1.dim() == 10); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, at) | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  |   Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config1.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   config1.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   config1.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   config1.insert(PointKey(2), l2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  |   EXPECT(assert_equal(x1, config1[PoseKey(1)])); | 
					
						
							|  |  |  |   EXPECT(assert_equal(x2, config1[PoseKey(2)])); | 
					
						
							|  |  |  |   EXPECT(assert_equal(l1, config1[PointKey(1)])); | 
					
						
							|  |  |  |   EXPECT(assert_equal(l2, config1[PointKey(2)])); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-20 22:51:00 +08:00
										 |  |  |   CHECK_EXCEPTION(config1[PoseKey(3)], std::invalid_argument); | 
					
						
							|  |  |  |   CHECK_EXCEPTION(config1[PointKey(3)], std::invalid_argument); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, zero_expmap_logmap) | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | { | 
					
						
							|  |  |  |   Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  |   Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   config1.insert(PoseKey(1), x1); | 
					
						
							|  |  |  |   config1.insert(PoseKey(2), x2); | 
					
						
							|  |  |  |   config1.insert(PointKey(1), l1); | 
					
						
							|  |  |  |   config1.insert(PointKey(2), l2); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ordering o; o += "x1", "x2", "l1", "l2"; | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues expected_zero(config1.dims(o)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   expected_zero[o["x1"]] = zero(3); | 
					
						
							|  |  |  |   expected_zero[o["x2"]] = zero(3); | 
					
						
							|  |  |  |   expected_zero[o["l1"]] = zero(2); | 
					
						
							|  |  |  |   expected_zero[o["l2"]] = zero(2); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   CHECK(assert_equal(expected_zero, config1.zero(o))); | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues delta(config1.dims(o)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   delta[o["x1"]] = Vector_(3, 1.0, 1.1, 1.2); | 
					
						
							|  |  |  |   delta[o["x2"]] = Vector_(3, 1.3, 1.4, 1.5); | 
					
						
							|  |  |  |   delta[o["l1"]] = Vector_(2, 1.0, 1.1); | 
					
						
							|  |  |  |   delta[o["l2"]] = Vector_(2, 1.3, 1.4); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values expected; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  |   expected.insert(PoseKey(1), x1.expmap(Vector_(3, 1.0, 1.1, 1.2))); | 
					
						
							|  |  |  |   expected.insert(PoseKey(2), x2.expmap(Vector_(3, 1.3, 1.4, 1.5))); | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  |   expected.insert(PointKey(1), Point2(5.0, 6.1)); | 
					
						
							|  |  |  |   expected.insert(PointKey(2), Point2(10.3, 11.4)); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   Values actual = config1.expmap(delta, o); | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  |   CHECK(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check log
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues expected_log = delta; | 
					
						
							|  |  |  |   VectorValues actual_log = config1.logmap(actual, o); | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  |   CHECK(assert_equal(expected_log, actual_log)); | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // some key types
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | typedef TypedSymbol<LieVector, 'L'> LamKey; | 
					
						
							| 
									
										
										
										
											2010-02-04 11:40:03 +08:00
										 |  |  | typedef TypedSymbol<Pose3, 'a'> Pose3Key; | 
					
						
							|  |  |  | typedef TypedSymbol<Point3, 'b'> Point3Key; | 
					
						
							|  |  |  | typedef TypedSymbol<Point3, 'c'> Point3Key2; | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // some config types
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | typedef LieValues<PoseKey> PoseValues; | 
					
						
							|  |  |  | typedef LieValues<PointKey> PointValues; | 
					
						
							|  |  |  | typedef LieValues<LamKey> LamValues; | 
					
						
							|  |  |  | typedef LieValues<Pose3Key> Pose3Values; | 
					
						
							|  |  |  | typedef LieValues<Point3Key> Point3Values; | 
					
						
							|  |  |  | typedef LieValues<Point3Key2> Point3Values2; | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | // some TupleValues types
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | typedef TupleValues<PoseValues, TupleValuesEnd<PointValues> > ValuesA; | 
					
						
							|  |  |  | typedef TupleValues<PoseValues, TupleValues<PointValues, TupleValuesEnd<LamValues> > > ValuesB; | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | typedef TupleValues1<PoseValues> TuplePoseValues; | 
					
						
							|  |  |  | typedef TupleValues1<PointValues> TuplePointValues; | 
					
						
							|  |  |  | typedef TupleValues2<PoseValues, PointValues> SimpleValues; | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, slicing) { | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 	PointKey l1(1), l2(2); | 
					
						
							|  |  |  | 	Point2 l1_val(1.0, 2.0), l2_val(3.0, 4.0); | 
					
						
							|  |  |  | 	PoseKey x1(1), x2(2); | 
					
						
							|  |  |  | 	Pose2 x1_val(1.0, 2.0, 0.3), x2_val(3.0, 4.0, 0.4); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	PoseValues liePoseValues; | 
					
						
							|  |  |  | 	liePoseValues.insert(x1, x1_val); | 
					
						
							|  |  |  | 	liePoseValues.insert(x2, x2_val); | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	PointValues liePointValues; | 
					
						
							|  |  |  | 	liePointValues.insert(l1, l1_val); | 
					
						
							|  |  |  | 	liePointValues.insert(l2, l2_val); | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | 	// construct TupleValues1 from the base config
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TuplePoseValues tupPoseValues1(liePoseValues); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(liePoseValues, tupPoseValues1.first(), tol)); | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TuplePointValues tupPointValues1(liePointValues); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(liePointValues, tupPointValues1.first(), tol)); | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | //	// construct a TupleValues2 from a TupleValues1
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	SimpleValues pairValues1(tupPoseValues1);
 | 
					
						
							|  |  |  | //	EXPECT(assert_equal(liePoseValues, pairValues1.first(), tol));
 | 
					
						
							|  |  |  | //	EXPECT(pairValues1.second().empty());
 | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | //
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	SimpleValues pairValues2(tupPointValues1);
 | 
					
						
							|  |  |  | //	EXPECT(assert_equal(liePointValues, pairValues2.second(), tol));
 | 
					
						
							|  |  |  | //	EXPECT(pairValues1.first().empty());
 | 
					
						
							| 
									
										
										
										
											2010-08-12 20:44:36 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, basic_functions) { | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 	// create some tuple configs
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesA configA; | 
					
						
							|  |  |  | 	ValuesB configB; | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	PoseKey x1(1); | 
					
						
							|  |  |  | 	PointKey l1(1); | 
					
						
							|  |  |  | 	LamKey L1(1); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	LieVector lam1 = LieVector(2.3); | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Insert
 | 
					
						
							|  |  |  | 	configA.insert(x1, pose1); | 
					
						
							|  |  |  | 	configA.insert(l1, point1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	configB.insert(x1, pose1); | 
					
						
							|  |  |  | 	configB.insert(l1, point1); | 
					
						
							|  |  |  | 	configB.insert(L1, lam1); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-03 21:57:34 +08:00
										 |  |  | 	// bracket operator
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(assert_equal(configA[x1], pose1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configA[l1], point1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB[x1], pose1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB[l1], point1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB[L1], lam1)); | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// exists
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configA.exists(x1)); | 
					
						
							|  |  |  | 	EXPECT(configA.exists(l1)); | 
					
						
							|  |  |  | 	EXPECT(configB.exists(x1)); | 
					
						
							|  |  |  | 	EXPECT(configB.exists(l1)); | 
					
						
							|  |  |  | 	EXPECT(configB.exists(L1)); | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-03 21:57:34 +08:00
										 |  |  | 	// at
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(assert_equal(configA.at(x1), pose1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configA.at(l1), point1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB.at(x1), pose1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB.at(l1), point1)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(configB.at(L1), lam1)); | 
					
						
							| 
									
										
										
										
											2010-02-03 22:08:09 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// size
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configA.size() == 2); | 
					
						
							|  |  |  | 	EXPECT(configB.size() == 3); | 
					
						
							| 
									
										
										
										
											2010-02-03 22:08:09 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// dim
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configA.dim() == 5); | 
					
						
							|  |  |  | 	EXPECT(configB.dim() == 6); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// erase
 | 
					
						
							|  |  |  | 	configA.erase(x1); | 
					
						
							|  |  |  | 	CHECK(!configA.exists(x1)); | 
					
						
							|  |  |  | 	CHECK(configA.size() == 1); | 
					
						
							|  |  |  | 	configA.erase(l1); | 
					
						
							|  |  |  | 	CHECK(!configA.exists(l1)); | 
					
						
							|  |  |  | 	CHECK(configA.size() == 0); | 
					
						
							|  |  |  | 	configB.erase(L1); | 
					
						
							|  |  |  | 	CHECK(!configB.exists(L1)); | 
					
						
							|  |  |  | 	CHECK(configB.size() == 2); | 
					
						
							| 
									
										
										
										
											2010-07-31 00:19:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// clear
 | 
					
						
							|  |  |  | 	configA.clear(); | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configA.size() == 0); | 
					
						
							| 
									
										
										
										
											2010-07-31 00:19:52 +08:00
										 |  |  | 	configB.clear(); | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configB.size() == 0); | 
					
						
							| 
									
										
										
										
											2010-07-31 00:19:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// empty
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(configA.empty()); | 
					
						
							|  |  |  | 	EXPECT(configB.empty()); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-25 10:50:01 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, insert_config) { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesB config1, config2, expected; | 
					
						
							| 
									
										
										
										
											2010-02-25 10:50:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	PoseKey x1(1), x2(2); | 
					
						
							|  |  |  | 	PointKey l1(1), l2(2); | 
					
						
							|  |  |  | 	LamKey L1(1), L2(2); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3), pose2(3.0, 4.0, 5.0); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0), point2(5.0, 6.0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	LieVector lam1 = LieVector(2.3), lam2 = LieVector(4.5); | 
					
						
							| 
									
										
										
										
											2010-02-25 10:50:01 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	config1.insert(x1, pose1); | 
					
						
							|  |  |  | 	config1.insert(l1, point1); | 
					
						
							|  |  |  | 	config1.insert(L1, lam1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	config2.insert(x2, pose2); | 
					
						
							|  |  |  | 	config2.insert(l2, point2); | 
					
						
							|  |  |  | 	config2.insert(L2, lam2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	config1.insert(config2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	expected.insert(x1, pose1); | 
					
						
							|  |  |  | 	expected.insert(l1, point1); | 
					
						
							|  |  |  | 	expected.insert(L1, lam1); | 
					
						
							|  |  |  | 	expected.insert(x2, pose2); | 
					
						
							|  |  |  | 	expected.insert(l2, point2); | 
					
						
							|  |  |  | 	expected.insert(L2, lam2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, config1)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-05-04 21:41:46 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, update_element ) | 
					
						
							| 
									
										
										
										
											2010-05-04 21:41:46 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues2<PoseValues, PointValues> cfg; | 
					
						
							| 
									
										
										
										
											2010-05-04 21:41:46 +08:00
										 |  |  | 	Pose2 x1(2.0, 1.0, 2.0), x2(3.0, 4.0, 5.0); | 
					
						
							|  |  |  | 	Point2 l1(1.0, 2.0), l2(3.0, 4.0); | 
					
						
							|  |  |  | 	PoseKey xk(1); | 
					
						
							|  |  |  | 	PointKey lk(1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	cfg.insert(xk, x1); | 
					
						
							|  |  |  | 	CHECK(cfg.size() == 1); | 
					
						
							|  |  |  | 	CHECK(assert_equal(x1, cfg.at(xk))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	cfg.update(xk, x2); | 
					
						
							|  |  |  | 	CHECK(cfg.size() == 1); | 
					
						
							|  |  |  | 	CHECK(assert_equal(x2, cfg.at(xk))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	cfg.insert(lk, l1); | 
					
						
							|  |  |  | 	CHECK(cfg.size() == 2); | 
					
						
							|  |  |  | 	CHECK(assert_equal(l1, cfg.at(lk))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	cfg.update(lk, l2); | 
					
						
							|  |  |  | 	CHECK(cfg.size() == 2); | 
					
						
							|  |  |  | 	CHECK(assert_equal(l2, cfg.at(lk))); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, equals ) | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	Pose2 x1(1,2,3), x2(6,7,8), x2_alt(5,6,7); | 
					
						
							|  |  |  | 	PoseKey x1k(1), x2k(2); | 
					
						
							|  |  |  | 	Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 	PointKey l1k(1), l2k(2); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesA config1, config2, config3, config4, config5; | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config1.insert(x1k, x1); | 
					
						
							|  |  |  | 	config1.insert(x2k, x2); | 
					
						
							|  |  |  | 	config1.insert(l1k, l1); | 
					
						
							|  |  |  | 	config1.insert(l2k, l2); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config2.insert(x1k, x1); | 
					
						
							|  |  |  | 	config2.insert(x2k, x2); | 
					
						
							|  |  |  | 	config2.insert(l1k, l1); | 
					
						
							|  |  |  | 	config2.insert(l2k, l2); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config3.insert(x2k, x2); | 
					
						
							|  |  |  | 	config3.insert(l1k, l1); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config4.insert(x1k, x1); | 
					
						
							|  |  |  | 	config4.insert(x2k, x2_alt); | 
					
						
							|  |  |  | 	config4.insert(l1k, l1); | 
					
						
							|  |  |  | 	config4.insert(l2k, l2); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesA config6(config1); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(assert_equal(config1,config2)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(config1,config1)); | 
					
						
							| 
									
										
										
										
											2010-08-31 04:54:12 +08:00
										 |  |  | 	EXPECT(assert_inequal(config1,config3)); | 
					
						
							|  |  |  | 	EXPECT(assert_inequal(config1,config4)); | 
					
						
							|  |  |  | 	EXPECT(assert_inequal(config1,config5)); | 
					
						
							| 
									
										
										
										
											2010-08-06 22:23:12 +08:00
										 |  |  | 	EXPECT(assert_equal(config1, config6)); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, expmap) | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  | 	PoseKey x1k(1), x2k(2); | 
					
						
							|  |  |  | 	Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 	PointKey l1k(1), l2k(2); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	Ordering o; o += "x1", "x2", "l1", "l2"; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesA config1; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config1.insert(x1k, x1); | 
					
						
							|  |  |  | 	config1.insert(x2k, x2); | 
					
						
							|  |  |  | 	config1.insert(l1k, l1); | 
					
						
							|  |  |  | 	config1.insert(l2k, l2); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues delta(config1.dims(o)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	delta[o["x1"]] = Vector_(3, 1.0, 1.1, 1.2); | 
					
						
							|  |  |  | 	delta[o["x2"]] = Vector_(3, 1.3, 1.4, 1.5); | 
					
						
							|  |  |  | 	delta[o["l1"]] = Vector_(2, 1.0, 1.1); | 
					
						
							|  |  |  | 	delta[o["l2"]] = Vector_(2, 1.3, 1.4); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	ValuesA expected; | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	expected.insert(x1k, x1.expmap(Vector_(3, 1.0, 1.1, 1.2))); | 
					
						
							|  |  |  | 	expected.insert(x2k, x2.expmap(Vector_(3, 1.3, 1.4, 1.5))); | 
					
						
							| 
									
										
										
										
											2010-02-04 10:04:45 +08:00
										 |  |  | 	expected.insert(l1k, Point2(5.0, 6.1)); | 
					
						
							|  |  |  | 	expected.insert(l2k, Point2(10.3, 11.4)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	CHECK(assert_equal(expected, config1.expmap(delta, o))); | 
					
						
							|  |  |  | 	CHECK(assert_equal(delta, config1.logmap(expected, o))); | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, expmap_typedefs) | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	Pose2 x1(1,2,3), x2(6,7,8); | 
					
						
							|  |  |  | 	PoseKey x1k(1), x2k(2); | 
					
						
							|  |  |  | 	Point2 l1(4,5), l2(9,10); | 
					
						
							|  |  |  | 	PointKey l1k(1), l2k(2); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ordering o; o += "x1", "x2", "l1", "l2"; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues2<PoseValues, PointValues> config1, expected, actual; | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	config1.insert(x1k, x1); | 
					
						
							|  |  |  | 	config1.insert(x2k, x2); | 
					
						
							|  |  |  | 	config1.insert(l1k, l1); | 
					
						
							|  |  |  | 	config1.insert(l2k, l2); | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues delta(config1.dims(o)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   delta[o["x1"]] = Vector_(3, 1.0, 1.1, 1.2); | 
					
						
							|  |  |  |   delta[o["x2"]] = Vector_(3, 1.3, 1.4, 1.5); | 
					
						
							|  |  |  |   delta[o["l1"]] = Vector_(2, 1.0, 1.1); | 
					
						
							|  |  |  |   delta[o["l2"]] = Vector_(2, 1.3, 1.4); | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	expected.insert(x1k, x1.expmap(Vector_(3, 1.0, 1.1, 1.2))); | 
					
						
							|  |  |  | 	expected.insert(x2k, x2.expmap(Vector_(3, 1.3, 1.4, 1.5))); | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | 	expected.insert(l1k, Point2(5.0, 6.1)); | 
					
						
							|  |  |  | 	expected.insert(l2k, Point2(10.3, 11.4)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	CHECK(assert_equal(expected, TupleValues2<PoseValues, PointValues>(config1.expmap(delta, o)))); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	//CHECK(assert_equal(delta, config1.logmap(expected)));
 | 
					
						
							| 
									
										
										
										
											2010-02-09 09:24:41 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-04 11:40:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, typedefs) | 
					
						
							| 
									
										
										
										
											2010-02-04 11:40:03 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues2<PoseValues, PointValues> config1; | 
					
						
							|  |  |  | 	TupleValues3<PoseValues, PointValues, LamValues> config2; | 
					
						
							|  |  |  | 	TupleValues4<PoseValues, PointValues, LamValues, Point3Values> config3; | 
					
						
							|  |  |  | 	TupleValues5<PoseValues, PointValues, LamValues, Point3Values, Pose3Values> config4; | 
					
						
							|  |  |  | 	TupleValues6<PoseValues, PointValues, LamValues, Point3Values, Pose3Values, Point3Values2> config5; | 
					
						
							| 
									
										
										
										
											2010-02-04 11:40:03 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-05 01:15:09 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST( TupleValues, pairconfig_style ) | 
					
						
							| 
									
										
										
										
											2010-02-05 01:15:09 +08:00
										 |  |  | { | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  | 	PoseKey x1(1); | 
					
						
							|  |  |  | 	PointKey l1(1); | 
					
						
							|  |  |  | 	LamKey L1(1); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	LieVector lam1 = LieVector(2.3); | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	PoseValues config1; config1.insert(x1, pose1); | 
					
						
							|  |  |  | 	PointValues config2; config2.insert(l1, point1); | 
					
						
							|  |  |  | 	LamValues config3; config3.insert(L1, lam1); | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Constructor
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues3<PoseValues, PointValues, LamValues> config(config1, config2, config3); | 
					
						
							| 
									
										
										
										
											2010-02-05 09:33:33 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// access
 | 
					
						
							| 
									
										
										
										
											2010-03-10 08:21:01 +08:00
										 |  |  | 	CHECK(assert_equal(config1, config.first())); | 
					
						
							|  |  |  | 	CHECK(assert_equal(config2, config.second())); | 
					
						
							|  |  |  | 	CHECK(assert_equal(config3, config.third())); | 
					
						
							| 
									
										
										
										
											2010-02-05 01:15:09 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-02-03 21:47:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-16 00:34:40 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, insert_config_typedef) { | 
					
						
							| 
									
										
										
										
											2010-03-16 00:34:40 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues4<PoseValues, PointValues, LamValues, Point3Values> config1, config2, expected; | 
					
						
							| 
									
										
										
										
											2010-03-16 00:34:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	PoseKey x1(1), x2(2); | 
					
						
							|  |  |  | 	PointKey l1(1), l2(2); | 
					
						
							|  |  |  | 	LamKey L1(1), L2(2); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3), pose2(3.0, 4.0, 5.0); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0), point2(5.0, 6.0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	LieVector lam1 = LieVector(2.3), lam2 = LieVector(4.5); | 
					
						
							| 
									
										
										
										
											2010-03-16 00:34:40 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	config1.insert(x1, pose1); | 
					
						
							|  |  |  | 	config1.insert(l1, point1); | 
					
						
							|  |  |  | 	config1.insert(L1, lam1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	config2.insert(x2, pose2); | 
					
						
							|  |  |  | 	config2.insert(l2, point2); | 
					
						
							|  |  |  | 	config2.insert(L2, lam2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	config1.insert(config2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	expected.insert(x1, pose1); | 
					
						
							|  |  |  | 	expected.insert(l1, point1); | 
					
						
							|  |  |  | 	expected.insert(L1, lam1); | 
					
						
							|  |  |  | 	expected.insert(x2, pose2); | 
					
						
							|  |  |  | 	expected.insert(l2, point2); | 
					
						
							|  |  |  | 	expected.insert(L2, lam2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, config1)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-02-06 13:10:25 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, partial_insert) { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues3<PoseValues, PointValues, LamValues> init, expected; | 
					
						
							| 
									
										
										
										
											2010-03-18 00:24:22 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	PoseKey x1(1), x2(2); | 
					
						
							|  |  |  | 	PointKey l1(1), l2(2); | 
					
						
							|  |  |  | 	LamKey L1(1), L2(2); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3), pose2(3.0, 4.0, 5.0); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0), point2(5.0, 6.0); | 
					
						
							| 
									
										
										
										
											2010-08-27 03:55:40 +08:00
										 |  |  | 	LieVector lam1 = LieVector(2.3), lam2 = LieVector(4.5); | 
					
						
							| 
									
										
										
										
											2010-02-06 13:10:25 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-03-18 00:24:22 +08:00
										 |  |  | 	init.insert(x1, pose1); | 
					
						
							|  |  |  | 	init.insert(l1, point1); | 
					
						
							|  |  |  | 	init.insert(L1, lam1); | 
					
						
							| 
									
										
										
										
											2010-02-06 13:10:25 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	PoseValues cfg1; | 
					
						
							| 
									
										
										
										
											2010-03-18 00:24:22 +08:00
										 |  |  | 	cfg1.insert(x2, pose2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	init.insertSub(cfg1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	expected.insert(x1, pose1); | 
					
						
							|  |  |  | 	expected.insert(l1, point1); | 
					
						
							|  |  |  | 	expected.insert(L1, lam1); | 
					
						
							|  |  |  | 	expected.insert(x2, pose2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, init)); | 
					
						
							| 
									
										
										
										
											2010-02-06 13:10:25 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-03-18 00:24:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-04-29 10:16:18 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:55 +08:00
										 |  |  | TEST(TupleValues, update) { | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	TupleValues3<PoseValues, PointValues, LamValues> init, superset, expected; | 
					
						
							| 
									
										
										
										
											2010-04-29 10:16:18 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	PoseKey x1(1), x2(2); | 
					
						
							|  |  |  | 	PointKey l1(1), l2(2); | 
					
						
							|  |  |  | 	Pose2 pose1(1.0, 2.0, 0.3), pose2(3.0, 4.0, 5.0); | 
					
						
							|  |  |  | 	Point2 point1(2.0, 3.0), point2(5.0, 6.0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	init.insert(x1, pose1); | 
					
						
							|  |  |  | 	init.insert(l1, point1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Pose2 pose1_(1.0, 2.0, 0.4); | 
					
						
							|  |  |  | 	Point2 point1_(2.0, 4.0); | 
					
						
							|  |  |  | 	superset.insert(x1, pose1_); | 
					
						
							|  |  |  | 	superset.insert(l1, point1_); | 
					
						
							|  |  |  | 	superset.insert(x2, pose2); | 
					
						
							|  |  |  | 	superset.insert(l2, point2); | 
					
						
							|  |  |  | 	init.update(superset); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	expected.insert(x1, pose1_); | 
					
						
							|  |  |  | 	expected.insert(l1, point1_); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	CHECK(assert_equal(expected, init)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-14 10:58:29 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ |