| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file testPoseRTV | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Testable.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/TestableAssertions.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/numericalDerivative.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:25 +08:00
										 |  |  | #include <gtsam_unstable/dynamics/PoseRTV.h>
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | GTSAM_CONCEPT_TESTABLE_INST(PoseRTV) | 
					
						
							|  |  |  | GTSAM_CONCEPT_LIE_INST(PoseRTV) | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  | static const Rot3 rot = Rot3::RzRyRx(0.1, 0.2, 0.3); | 
					
						
							|  |  |  | static const Point3 pt(1.0, 2.0, 3.0); | 
					
						
							|  |  |  | static const Velocity3 vel(0.4, 0.5, 0.6); | 
					
						
							|  |  |  | static const Vector3 kZero3 = Vector3::Zero(); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, constructors ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PoseRTV state1(pt, rot, vel); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(pt, state1.t())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(rot, state1.R())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(vel, state1.v())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(Pose3(rot, pt), state1.pose())); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   PoseRTV state2; | 
					
						
							| 
									
										
										
										
											2016-02-12 08:52:02 +08:00
										 |  |  |   EXPECT(assert_equal(Point3(0,0,0),  state2.t())); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(Rot3(), state2.R())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(kZero3, state2.v())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(Pose3(), state2.pose())); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   PoseRTV state3(Pose3(rot, pt), vel); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(pt,  state3.t())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(rot, state3.R())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(vel, state3.v())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(Pose3(rot, pt), state3.pose())); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   PoseRTV state4(Pose3(rot, pt)); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(pt,  state4.t())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(rot, state4.R())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(kZero3, state4.v())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(Pose3(rot, pt), state4.pose())); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Vector vec_init = (Vector(9) << 0.1, 0.2, 0.3,  1.0, 2.0, 3.0,  0.4, 0.5, 0.6).finished(); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PoseRTV state5(vec_init); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(pt,  state5.t())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(rot, state5.R())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(vel, state5.v())); | 
					
						
							|  |  |  |   EXPECT(assert_equal(vec_init, state5.vector())); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, dim ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PoseRTV state1(pt, rot, vel); | 
					
						
							|  |  |  |   EXPECT_LONGS_EQUAL(9, state1.dim()); | 
					
						
							|  |  |  |   EXPECT_LONGS_EQUAL(9, PoseRTV::Dim()); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, equals ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   PoseRTV state1, state2(pt, rot, vel), state3(state2), state4(Pose3(rot, pt)); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(state1, state1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(state2, state3)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(state3, state2)); | 
					
						
							|  |  |  |   EXPECT(assert_inequal(state1, state2)); | 
					
						
							|  |  |  |   EXPECT(assert_inequal(state2, state1)); | 
					
						
							|  |  |  |   EXPECT(assert_inequal(state2, state4)); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, Lie ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // origin and zero deltas
 | 
					
						
							| 
									
										
										
										
											2015-05-26 14:50:00 +08:00
										 |  |  |   PoseRTV identity; | 
					
						
							| 
									
										
										
										
											2016-04-16 04:54:46 +08:00
										 |  |  |   EXPECT(assert_equal(identity, (PoseRTV)identity.retract(Z_9x1))); | 
					
						
							|  |  |  |   EXPECT(assert_equal((Vector) Z_9x1, identity.localCoordinates(identity))); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   PoseRTV state1(pt, rot, vel); | 
					
						
							| 
									
										
										
										
											2016-04-16 04:54:46 +08:00
										 |  |  |   EXPECT(assert_equal(state1, (PoseRTV)state1.retract(Z_9x1))); | 
					
						
							|  |  |  |   EXPECT(assert_equal((Vector) Z_9x1, state1.localCoordinates(state1))); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-17 13:38:30 +08:00
										 |  |  |   Vector delta(9); | 
					
						
							|  |  |  |   delta << 0.1, 0.1, 0.1, 0.2, 0.3, 0.4,-0.1,-0.2,-0.3; | 
					
						
							| 
									
										
										
										
											2015-07-17 14:48:56 +08:00
										 |  |  |   Pose3 pose2 = Pose3(rot, pt).retract(delta.head<6>()); | 
					
						
							|  |  |  |   Velocity3 vel2 = vel + Velocity3(-0.1, -0.2, -0.3); | 
					
						
							|  |  |  |   PoseRTV state2(pose2.translation(), pose2.rotation(), vel2); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(state2, (PoseRTV)state1.retract(delta))); | 
					
						
							|  |  |  |   EXPECT(assert_equal(delta, state1.localCoordinates(state2))); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-17 13:38:30 +08:00
										 |  |  |   // roundtrip from state2 to state3 and back
 | 
					
						
							|  |  |  |   PoseRTV state3 = state2.retract(delta); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(delta, state2.localCoordinates(state3))); | 
					
						
							| 
									
										
										
										
											2015-07-17 13:38:30 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-17 14:48:56 +08:00
										 |  |  |   // roundtrip from state3 to state4 and back, with expmap.
 | 
					
						
							| 
									
										
										
										
											2015-07-17 13:38:30 +08:00
										 |  |  |   PoseRTV state4 = state3.expmap(delta); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(delta, state3.logmap(state4))); | 
					
						
							| 
									
										
										
										
											2015-07-17 14:48:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // For the expmap/logmap (not necessarily retract/local) -delta goes other way
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(state3, (PoseRTV)state4.expmap(-delta))); | 
					
						
							|  |  |  |   EXPECT(assert_equal(delta, -state4.logmap(state3))); | 
					
						
							| 
									
										
										
										
											2015-05-24 10:36:42 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, dynamics_identities ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // general dynamics should produce the same measurements as the imuPrediction function
 | 
					
						
							|  |  |  |   PoseRTV x0, x1, x2, x3, x4; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   const double dt = 0.1; | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector accel = Vector3(0.2, 0.0, 0.0), gyro = Vector3(0.0, 0.0, 0.2); | 
					
						
							| 
									
										
										
										
											2016-04-16 04:54:46 +08:00
										 |  |  |   Vector imu01 = Z_6x1, imu12 = Z_6x1, imu23 = Z_6x1, imu34 = Z_6x1; | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   x1 = x0.generalDynamics(accel, gyro, dt); | 
					
						
							|  |  |  |   x2 = x1.generalDynamics(accel, gyro, dt); | 
					
						
							|  |  |  |   x3 = x2.generalDynamics(accel, gyro, dt); | 
					
						
							|  |  |  |   x4 = x3.generalDynamics(accel, gyro, dt); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  | //  EXPECT(assert_equal(imu01, x0.imuPrediction(x1, dt).first));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(imu12, x1.imuPrediction(x2, dt).first));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(imu23, x2.imuPrediction(x3, dt).first));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(imu34, x3.imuPrediction(x4, dt).first));
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | //
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  | //  EXPECT(assert_equal(x1.translation(), x0.imuPrediction(x1, dt).second));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(x2.translation(), x1.imuPrediction(x2, dt).second));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(x3.translation(), x2.imuPrediction(x3, dt).second));
 | 
					
						
							|  |  |  | //  EXPECT(assert_equal(x4.translation(), x3.imuPrediction(x4, dt).second));
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-05-26 16:08:27 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | PoseRTV compose_proxy(const PoseRTV& A, const PoseRTV& B) { return A.compose(B); } | 
					
						
							|  |  |  | TEST( testPoseRTV, compose ) { | 
					
						
							|  |  |  |   PoseRTV state1(pt, rot, vel), state2 = state1; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix actH1, actH2; | 
					
						
							|  |  |  |   state1.compose(state2, actH1, actH2); | 
					
						
							|  |  |  |   Matrix numericH1 = numericalDerivative21(compose_proxy, state1, state2); | 
					
						
							|  |  |  |   Matrix numericH2 = numericalDerivative22(compose_proxy, state1, state2); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numericH1, actH1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(numericH2, actH2)); | 
					
						
							| 
									
										
										
										
											2015-05-26 16:08:27 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | PoseRTV between_proxy(const PoseRTV& A, const PoseRTV& B) { return A.between(B); } | 
					
						
							|  |  |  | TEST( testPoseRTV, between ) { | 
					
						
							|  |  |  |   PoseRTV state1(pt, rot, vel), state2 = state1; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix actH1, actH2; | 
					
						
							|  |  |  |   state1.between(state2, actH1, actH2); | 
					
						
							|  |  |  |   Matrix numericH1 = numericalDerivative21(between_proxy, state1, state2); | 
					
						
							|  |  |  |   Matrix numericH2 = numericalDerivative22(between_proxy, state1, state2); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numericH1, actH1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(numericH2, actH2)); | 
					
						
							| 
									
										
										
										
											2015-05-26 16:08:27 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | PoseRTV inverse_proxy(const PoseRTV& A) { return A.inverse(); } | 
					
						
							|  |  |  | TEST( testPoseRTV, inverse ) { | 
					
						
							|  |  |  |   PoseRTV state1(pt, rot, vel); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix actH1; | 
					
						
							|  |  |  |   state1.inverse(actH1); | 
					
						
							|  |  |  |   Matrix numericH1 = numericalDerivative11(inverse_proxy, state1); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numericH1, actH1)); | 
					
						
							| 
									
										
										
										
											2015-05-26 16:08:27 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | double range_proxy(const PoseRTV& A, const PoseRTV& B) { return A.range(B); } | 
					
						
							|  |  |  | TEST( testPoseRTV, range ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Point3 tA(1.0, 2.0, 3.0), tB(3.0, 2.0, 3.0); | 
					
						
							|  |  |  |   PoseRTV rtvA(tA), rtvB(tB); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT_DOUBLES_EQUAL(0.0, rtvA.range(rtvA), 1e-9); | 
					
						
							|  |  |  |   EXPECT_DOUBLES_EQUAL(2.0, rtvA.range(rtvB), 1e-9); | 
					
						
							|  |  |  |   EXPECT_DOUBLES_EQUAL(2.0, rtvB.range(rtvA), 1e-9); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix actH1, actH2; | 
					
						
							|  |  |  |   rtvA.range(rtvB, actH1, actH2); | 
					
						
							|  |  |  |   Matrix numericH1 = numericalDerivative21(range_proxy, rtvA, rtvB); | 
					
						
							|  |  |  |   Matrix numericH2 = numericalDerivative22(range_proxy, rtvA, rtvB); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numericH1, actH1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(numericH2, actH2)); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | PoseRTV transformed_from_proxy(const PoseRTV& a, const Pose3& trans) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   return a.transformed_from(trans); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | TEST( testPoseRTV, transformed_from_1 ) { | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |   Rot3 R = Rot3::Rodrigues(0.1, 0.2, 0.3); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Point3 T(1.0, 2.0, 3.0); | 
					
						
							|  |  |  |   Velocity3 V(2.0, 3.0, 4.0); | 
					
						
							|  |  |  |   PoseRTV start(R, T, V); | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix actDTrans, actDGlobal; | 
					
						
							|  |  |  |   PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); | 
					
						
							| 
									
										
										
										
											2015-07-18 08:36:29 +08:00
										 |  |  |   PoseRTV expected(transform.compose(start.pose()), transform.rotation().matrix() * V); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails
 | 
					
						
							|  |  |  |   Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numDGlobal, actDGlobal)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(numDTrans, actDTrans, 1e-5)); // FIXME: still needs analytic derivative
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testPoseRTV, transformed_from_2 ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   Rot3 R; | 
					
						
							|  |  |  |   Point3 T(1.0, 2.0, 3.0); | 
					
						
							|  |  |  |   Velocity3 V(2.0, 3.0, 4.0); | 
					
						
							|  |  |  |   PoseRTV start(R, T, V); | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   Pose3 transform(Rot3::Yaw(M_PI_2), Point3(1.0, 2.0, 3.0)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix actDTrans, actDGlobal; | 
					
						
							|  |  |  |   PoseRTV actual = start.transformed_from(transform, actDGlobal, actDTrans); | 
					
						
							| 
									
										
										
										
											2015-07-18 08:36:29 +08:00
										 |  |  |   PoseRTV expected(transform.compose(start.pose()), transform.rotation().matrix() * V); | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix numDGlobal = numericalDerivative21(transformed_from_proxy, start, transform, 1e-5); // At 1e-8, fails
 | 
					
						
							|  |  |  |   Matrix numDTrans = numericalDerivative22(transformed_from_proxy, start, transform, 1e-8); // Sensitive to step size
 | 
					
						
							| 
									
										
										
										
											2015-07-24 22:05:15 +08:00
										 |  |  |   EXPECT(assert_equal(numDGlobal, actDGlobal)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(numDTrans, actDTrans, 1e-5)); // FIXME: still needs analytic derivative
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2012-06-06 21:04:47 +08:00
										 |  |  | TEST(testPoseRTV, RRTMbn) { | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   EXPECT(assert_equal(I_3x3, PoseRTV::RRTMbn(kZero3))); | 
					
						
							|  |  |  |   EXPECT(assert_equal(I_3x3, PoseRTV::RRTMbn(Rot3()))); | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   EXPECT(assert_equal(PoseRTV::RRTMbn(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMbn(Rot3::Ypr(0.1, 0.2, 0.3)))); | 
					
						
							| 
									
										
										
										
											2012-06-06 21:04:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(testPoseRTV, RRTMnb) { | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   EXPECT(assert_equal(I_3x3, PoseRTV::RRTMnb(kZero3))); | 
					
						
							|  |  |  |   EXPECT(assert_equal(I_3x3, PoseRTV::RRTMnb(Rot3()))); | 
					
						
							| 
									
										
										
										
											2016-01-27 15:09:58 +08:00
										 |  |  |   EXPECT(assert_equal(PoseRTV::RRTMnb(Vector3(0.3, 0.2, 0.1)), PoseRTV::RRTMnb(Rot3::Ypr(0.1, 0.2, 0.3)))); | 
					
						
							| 
									
										
										
										
											2012-06-06 21:04:47 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |