| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  *  @file  testPose3Graph.cpp | 
					
						
							|  |  |  |  *  @authors Frank Dellaert, Viorela Ila | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <boost/shared_ptr.hpp>
 | 
					
						
							|  |  |  | #include <boost/assign/std/list.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  | using namespace boost; | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | // TODO: DANGEROUS, create shared pointers
 | 
					
						
							|  |  |  | #define GTSAM_MAGIC_GAUSSIAN 6
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-17 03:37:17 +08:00
										 |  |  | #include "pose3SLAM.h"
 | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | #include "Ordering.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // common measurement covariance
 | 
					
						
							|  |  |  | static Matrix covariance = eye(6); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // test optimization with 6 poses arranged in a hexagon and a loop closure
 | 
					
						
							|  |  |  | TEST(Pose3Graph, optimizeCircle) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// Create a hexagon of poses
 | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  | 	double radius = 10; | 
					
						
							|  |  |  | 	Pose3Config hexagon = pose3SLAM::circle(6,radius); | 
					
						
							|  |  |  |   Pose3 gT0 = hexagon[0], gT1 = hexagon[1]; | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// create a Pose graph with one equality constraint and one measurement
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  |   shared_ptr<Pose3Graph> fg(new Pose3Graph); | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  |   fg->addHardConstraint(0, gT0); | 
					
						
							|  |  |  |   Pose3 _0T1 = between(gT0,gT1); // inv(gT0)*gT1
 | 
					
						
							|  |  |  |   double theta = M_PI/3.0; | 
					
						
							|  |  |  |   CHECK(assert_equal(Pose3(Rot3::yaw(-theta),Point3(radius*sin(theta),-radius*cos(theta),0)),_0T1)); | 
					
						
							|  |  |  |   fg->addConstraint(0,1, _0T1, covariance); | 
					
						
							|  |  |  |   fg->addConstraint(1,2, _0T1, covariance); | 
					
						
							|  |  |  |   fg->addConstraint(2,3, _0T1, covariance); | 
					
						
							|  |  |  |   fg->addConstraint(3,4, _0T1, covariance); | 
					
						
							|  |  |  |   fg->addConstraint(4,5, _0T1, covariance); | 
					
						
							|  |  |  |   fg->addConstraint(5,0, _0T1, covariance); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create initial config
 | 
					
						
							|  |  |  |   boost::shared_ptr<Pose3Config> initial(new Pose3Config()); | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  |   initial->insert(0, gT0); | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |   initial->insert(1, expmap(hexagon[1],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); | 
					
						
							|  |  |  |   initial->insert(2, expmap(hexagon[2],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); | 
					
						
							|  |  |  |   initial->insert(3, expmap(hexagon[3],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); | 
					
						
							|  |  |  |   initial->insert(4, expmap(hexagon[4],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1))); | 
					
						
							|  |  |  |   initial->insert(5, expmap(hexagon[5],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1))); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Choose an ordering and optimize
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  |   shared_ptr<Ordering> ordering(new Ordering); | 
					
						
							| 
									
										
											  
											
												Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just  says something like
	if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
											
										 
											2010-01-14 06:25:03 +08:00
										 |  |  |   *ordering += "x0","x1","x2","x3","x4","x5"; | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  |   typedef NonlinearOptimizer<Pose3Graph, Pose3Config> Optimizer; | 
					
						
							| 
									
										
										
										
											2010-01-20 10:28:23 +08:00
										 |  |  | 	Optimizer::shared_solver solver(new Optimizer::solver(ordering)); | 
					
						
							|  |  |  |   Optimizer optimizer0(fg, initial, solver); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  |   Optimizer::verbosityLevel verbosity = Optimizer::SILENT; | 
					
						
							|  |  |  | //  Optimizer::verbosityLevel verbosity = Optimizer::ERROR;
 | 
					
						
							| 
									
										
										
										
											2010-01-12 04:17:28 +08:00
										 |  |  |   Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Pose3Config actual = *optimizer.config(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Check with ground truth
 | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  |   CHECK(assert_equal(hexagon, actual,1e-4)); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Check loop closure
 | 
					
						
							| 
									
										
										
										
											2010-01-27 04:00:17 +08:00
										 |  |  |   CHECK(assert_equal(_0T1,between(actual[5],actual[0]),1e-5)); | 
					
						
							| 
									
										
										
										
											2010-01-11 02:21:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |