| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file testIMUSystem | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 03:17:15 +08:00
										 |  |  | #include <iostream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-23 02:49:07 +08:00
										 |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/PriorFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/RangeFactor.h>
 | 
					
						
							| 
									
										
										
										
											2012-08-25 05:39:56 +08:00
										 |  |  | #include <gtsam_unstable/slam/PartialPriorFactor.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-23 02:49:07 +08:00
										 |  |  | #include <gtsam/nonlinear/NonlinearEquality.h>
 | 
					
						
							| 
									
										
										
										
											2012-08-05 03:48:52 +08:00
										 |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-23 02:49:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam_unstable/dynamics/IMUFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/dynamics/FullIMUFactor.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/dynamics/VelocityConstraint.h>
 | 
					
						
							|  |  |  | #include <gtsam_unstable/dynamics/DynamicsPriors.h>
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-08 22:33:59 +08:00
										 |  |  | using namespace std; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | const double tol=1e-5; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 03:17:15 +08:00
										 |  |  | static const Key x0 = 0, x1 = 1, x2 = 2, x3 = 3, x4 = 4; | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | static const Vector g = delta(3, 2, -9.81); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(testIMUSystem, instantiations) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // just checking for compilation
 | 
					
						
							|  |  |  |   PoseRTV x1_v; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   gtsam::SharedNoiseModel model1 = gtsam::noiseModel::Unit::Create(1); | 
					
						
							|  |  |  |   gtsam::SharedNoiseModel model3 = gtsam::noiseModel::Unit::Create(3); | 
					
						
							|  |  |  |   gtsam::SharedNoiseModel model6 = gtsam::noiseModel::Unit::Create(6); | 
					
						
							|  |  |  |   gtsam::SharedNoiseModel model9 = gtsam::noiseModel::Unit::Create(9); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Vector accel = ones(3), gyro = ones(3); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   IMUFactor<PoseRTV> imu(accel, gyro, 0.01, x1, x2, model6); | 
					
						
							|  |  |  |   FullIMUFactor<PoseRTV> full_imu(accel, gyro, 0.01, x1, x2, model9); | 
					
						
							|  |  |  |   NonlinearEquality<gtsam::PoseRTV> poseHardPrior(x1, x1_v); | 
					
						
							|  |  |  |   BetweenFactor<gtsam::PoseRTV> odom(x1, x2, x1_v, model9); | 
					
						
							|  |  |  |   RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> range(x1, x2, 1.0, model1); | 
					
						
							|  |  |  |   VelocityConstraint constraint(x1, x2, 0.1, 10000); | 
					
						
							|  |  |  |   PriorFactor<gtsam::PoseRTV> posePrior(x1, x1_v, model9); | 
					
						
							|  |  |  |   DHeightPrior heightPrior(x1, 0.1, model1); | 
					
						
							|  |  |  |   VelocityPrior velPrior(x1, ones(3), model3); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testIMUSystem, optimize_chain ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create a simple chain of poses to generate IMU measurements
 | 
					
						
							|  |  |  |   const double dt = 1.0; | 
					
						
							|  |  |  |   PoseRTV pose1, | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |           pose2(Point3(1.0, 1.0, 0.0), Rot3::ypr(0.1, 0.0, 0.0), (Vector)Vector3(2.0, 2.0, 0.0)), | 
					
						
							|  |  |  |           pose3(Point3(2.0, 2.0, 0.0), Rot3::ypr(0.2, 0.0, 0.0), (Vector)Vector3(0.0, 0.0, 0.0)), | 
					
						
							|  |  |  |           pose4(Point3(3.0, 3.0, 0.0), Rot3::ypr(0.3, 0.0, 0.0), (Vector)Vector3(2.0, 2.0, 0.0)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create measurements
 | 
					
						
							|  |  |  |   SharedDiagonal model = noiseModel::Unit::Create(6); | 
					
						
							| 
									
										
										
										
											2014-11-04 22:41:14 +08:00
										 |  |  |   Vector6 imu12 = pose1.imuPrediction(pose2, dt); | 
					
						
							|  |  |  |   Vector6 imu23 = pose2.imuPrediction(pose3, dt); | 
					
						
							|  |  |  |   Vector6 imu34 = pose3.imuPrediction(pose4, dt); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // assemble simple graph with IMU measurements and velocity constraints
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2013-08-12 02:40:47 +08:00
										 |  |  |   graph += NonlinearEquality<gtsam::PoseRTV>(x1, pose1); | 
					
						
							|  |  |  |   graph += IMUFactor<PoseRTV>(imu12, dt, x1, x2, model); | 
					
						
							|  |  |  |   graph += IMUFactor<PoseRTV>(imu23, dt, x2, x3, model); | 
					
						
							|  |  |  |   graph += IMUFactor<PoseRTV>(imu34, dt, x3, x4, model); | 
					
						
							|  |  |  |   graph += VelocityConstraint(x1, x2, dt); | 
					
						
							|  |  |  |   graph += VelocityConstraint(x2, x3, dt); | 
					
						
							|  |  |  |   graph += VelocityConstraint(x3, x4, dt); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // ground truth values
 | 
					
						
							|  |  |  |   Values true_values; | 
					
						
							|  |  |  |   true_values.insert(x1, pose1); | 
					
						
							|  |  |  |   true_values.insert(x2, pose2); | 
					
						
							|  |  |  |   true_values.insert(x3, pose3); | 
					
						
							|  |  |  |   true_values.insert(x4, pose4); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // verify zero error
 | 
					
						
							|  |  |  |   EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // initialize with zero values and optimize
 | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   values.insert(x1, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x2, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x3, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x4, PoseRTV()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(true_values, actual, tol)); | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testIMUSystem, optimize_chain_fullfactor ) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create a simple chain of poses to generate IMU measurements
 | 
					
						
							|  |  |  |   const double dt = 1.0; | 
					
						
							|  |  |  |   PoseRTV pose1, | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |           pose2(Point3(1.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), (Vector)Vector3(1.0, 0.0, 0.0)), | 
					
						
							|  |  |  |           pose3(Point3(2.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), (Vector)Vector3(1.0, 0.0, 0.0)), | 
					
						
							|  |  |  |           pose4(Point3(3.0, 0.0, 0.0), Rot3::ypr(0.0, 0.0, 0.0), (Vector)Vector3(1.0, 0.0, 0.0)); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // create measurements
 | 
					
						
							|  |  |  |   SharedDiagonal model = noiseModel::Isotropic::Sigma(9, 1.0); | 
					
						
							| 
									
										
										
										
											2014-11-04 22:41:14 +08:00
										 |  |  |   Vector6 imu12 = pose1.imuPrediction(pose2, dt); | 
					
						
							|  |  |  |   Vector6 imu23 = pose2.imuPrediction(pose3, dt); | 
					
						
							|  |  |  |   Vector6 imu34 = pose3.imuPrediction(pose4, dt); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // assemble simple graph with IMU measurements and velocity constraints
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2013-08-12 02:40:47 +08:00
										 |  |  |   graph += NonlinearEquality<gtsam::PoseRTV>(x1, pose1); | 
					
						
							|  |  |  |   graph += FullIMUFactor<PoseRTV>(imu12, dt, x1, x2, model); | 
					
						
							|  |  |  |   graph += FullIMUFactor<PoseRTV>(imu23, dt, x2, x3, model); | 
					
						
							|  |  |  |   graph += FullIMUFactor<PoseRTV>(imu34, dt, x3, x4, model); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // ground truth values
 | 
					
						
							|  |  |  |   Values true_values; | 
					
						
							|  |  |  |   true_values.insert(x1, pose1); | 
					
						
							|  |  |  |   true_values.insert(x2, pose2); | 
					
						
							|  |  |  |   true_values.insert(x3, pose3); | 
					
						
							|  |  |  |   true_values.insert(x4, pose4); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // verify zero error
 | 
					
						
							|  |  |  |   EXPECT_DOUBLES_EQUAL(0, graph.error(true_values), 1e-5); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // initialize with zero values and optimize
 | 
					
						
							|  |  |  |   Values values; | 
					
						
							|  |  |  |   values.insert(x1, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x2, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x3, PoseRTV()); | 
					
						
							|  |  |  |   values.insert(x4, PoseRTV()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   cout << "Initial Error: " << graph.error(values) << endl; // Initial error is 0.5 - need better prediction model
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values actual = LevenbergMarquardtOptimizer(graph, values).optimize(); | 
					
						
							|  |  |  | //  EXPECT(assert_equal(true_values, actual, tol)); // FAIL
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( testIMUSystem, linear_trajectory) { | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   // create a linear trajectory of poses
 | 
					
						
							|  |  |  |   // and verify simple solution
 | 
					
						
							|  |  |  |   const double dt = 1.0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   PoseRTV start; | 
					
						
							|  |  |  |   Vector accel = delta(3, 0, 0.5); // forward force
 | 
					
						
							|  |  |  |   Vector gyro = delta(3, 0, 0.1); // constant rotation
 | 
					
						
							|  |  |  |   SharedDiagonal model = noiseModel::Unit::Create(9); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Values true_traj, init_traj; | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-08-12 02:40:47 +08:00
										 |  |  |   graph += NonlinearEquality<gtsam::PoseRTV>(x0, start); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |   true_traj.insert(x0, start); | 
					
						
							|  |  |  |   init_traj.insert(x0, start); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   size_t nrPoses = 10; | 
					
						
							|  |  |  |   PoseRTV cur_pose = start; | 
					
						
							|  |  |  |   for (size_t i=1; i<nrPoses; ++i) { | 
					
						
							|  |  |  |     Key xA = i-1, xB = i; | 
					
						
							|  |  |  |     cur_pose = cur_pose.generalDynamics(accel, gyro, dt); | 
					
						
							| 
									
										
										
										
											2013-08-12 02:40:47 +08:00
										 |  |  |     graph += FullIMUFactor<PoseRTV>(accel - g, gyro, dt, xA, xB, model); | 
					
						
							| 
									
										
										
										
											2012-10-02 22:40:07 +08:00
										 |  |  |     true_traj.insert(xB, cur_pose); | 
					
						
							|  |  |  |     init_traj.insert(xB, PoseRTV()); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | //  EXPECT_DOUBLES_EQUAL(0, graph.error(true_traj), 1e-5); // FAIL
 | 
					
						
							| 
									
										
										
										
											2012-05-04 01:03:16 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ |