| 
									
										
										
										
											2009-11-13 00:41:18 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * @file testNonlinearEquality.cpp | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | #include "VectorConfig.h"
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:41:18 +08:00
										 |  |  | #include "NonlinearEquality.h"
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | typedef NonlinearEquality<VectorConfig,string,Vector> NLE; | 
					
						
							|  |  |  | typedef boost::shared_ptr<NLE> shared_nle; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | bool vector_compare(const Vector& a, const Vector& b) { | 
					
						
							|  |  |  | 	return equal_with_abs_tol(a, b, 1e-5); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-28 01:59:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | TEST ( NonlinearEquality, linearization ) { | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  | 	Symbol key = "x"; | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	Vector value = Vector_(2, 1.0, 2.0); | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	VectorConfig linearize; | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	linearize.insert(key, value); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// create a nonlinear equality constraint
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	shared_nle nle(new NLE(key, value,vector_compare)); | 
					
						
							| 
									
										
										
										
											2009-11-13 00:47:12 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	// check linearize
 | 
					
						
							| 
									
										
										
										
											2010-01-23 01:36:57 +08:00
										 |  |  | 	SharedDiagonal constraintModel = noiseModel::Constrained::All(2); | 
					
						
							| 
									
										
										
										
											2010-01-21 02:32:48 +08:00
										 |  |  | 	GaussianFactor expLF(key, eye(2), zero(2), constraintModel); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	GaussianFactor::shared_ptr actualLF = nle->linearize(linearize); | 
					
						
							|  |  |  | 	CHECK(assert_equal(*actualLF, expLF)); | 
					
						
							| 
									
										
										
										
											2009-11-13 00:41:18 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | /* ********************************************************************** */ | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | TEST ( NonlinearEquality, linearization_fail ) { | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  |   Symbol key = "x"; | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	Vector value = Vector_(2, 1.0, 2.0); | 
					
						
							|  |  |  | 	Vector wrong = Vector_(2, 3.0, 4.0); | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	VectorConfig bad_linearize; | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	bad_linearize.insert(key, wrong); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// create a nonlinear equality constraint
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	shared_nle nle(new NLE(key, value,vector_compare)); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// check linearize to ensure that it fails for bad linearization points
 | 
					
						
							|  |  |  | 	try { | 
					
						
							|  |  |  | 		GaussianFactor::shared_ptr actualLF = nle->linearize(bad_linearize); | 
					
						
							|  |  |  | 		CHECK(false); | 
					
						
							|  |  |  | 	} catch (std::invalid_argument) { | 
					
						
							|  |  |  | 		CHECK(true); | 
					
						
							|  |  |  | 	} | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-28 01:59:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | TEST ( NonlinearEquality, error ) { | 
					
						
							| 
									
										
										
										
											2010-01-18 03:34:57 +08:00
										 |  |  |   Symbol key = "x"; | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	Vector value = Vector_(2, 1.0, 2.0); | 
					
						
							|  |  |  | 	Vector wrong = Vector_(2, 3.0, 4.0); | 
					
						
							|  |  |  | 	VectorConfig feasible, bad_linearize; | 
					
						
							|  |  |  | 	feasible.insert(key, value); | 
					
						
							|  |  |  | 	bad_linearize.insert(key, wrong); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// create a nonlinear equality constraint
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	shared_nle nle(new NLE(key, value,vector_compare)); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// check error function outputs
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	Vector actual = nle->unwhitenedError(feasible); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	CHECK(assert_equal(actual, zero(2))); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-01-18 13:38:53 +08:00
										 |  |  | 	actual = nle->unwhitenedError(bad_linearize); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	CHECK(assert_equal(actual, repeat(2, 1.0/0.0))); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-28 01:59:03 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | TEST ( NonlinearEquality, equals ) { | 
					
						
							|  |  |  | 	string key1 = "x"; | 
					
						
							|  |  |  | 	Vector value1 = Vector_(2, 1.0, 2.0); | 
					
						
							|  |  |  | 	Vector value2 = Vector_(2, 3.0, 4.0); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// create some constraints to compare
 | 
					
						
							| 
									
										
											  
											
												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
										 |  |  | 	shared_nle nle1(new NLE(key1, value1,vector_compare)); | 
					
						
							|  |  |  | 	shared_nle nle2(new NLE(key1, value1,vector_compare)); | 
					
						
							|  |  |  | 	shared_nle nle3(new NLE(key1, value2,vector_compare)); | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// verify
 | 
					
						
							| 
									
										
										
										
											2009-11-28 01:59:03 +08:00
										 |  |  | 	CHECK(nle1->equals(*nle2));  // basic equality = true
 | 
					
						
							|  |  |  | 	CHECK(nle2->equals(*nle1));  // test symmetry of equals()
 | 
					
						
							| 
									
										
										
										
											2009-11-13 10:06:52 +08:00
										 |  |  | 	CHECK(!nle1->equals(*nle3)); // test config
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2009-11-13 00:41:18 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ |