2009-12-10 01:29:43 +08:00
|
|
|
/**
|
2010-01-10 21:55:55 +08:00
|
|
|
* @file testPose2Factor.cpp
|
2009-12-10 07:43:01 +08:00
|
|
|
* @brief Unit tests for Pose2Factor Class
|
2009-12-10 01:29:43 +08:00
|
|
|
* @authors Frank Dellaert, Viorela Ila
|
|
|
|
**/
|
|
|
|
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
2010-01-18 03:34:57 +08:00
|
|
|
|
|
|
|
#define GTSAM_MAGIC_KEY
|
|
|
|
|
2010-01-10 21:55:55 +08:00
|
|
|
#include "numericalDerivative.h"
|
2010-01-17 02:01:16 +08:00
|
|
|
#include "pose2SLAM.h"
|
2009-12-10 01:29:43 +08:00
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
using namespace gtsam;
|
|
|
|
|
2010-01-10 21:55:55 +08:00
|
|
|
// Common measurement covariance
|
|
|
|
static double sx=0.5, sy=0.5,st=0.1;
|
2010-01-18 13:38:53 +08:00
|
|
|
static noiseModel::Gaussian::shared_ptr covariance(
|
|
|
|
noiseModel::Gaussian::Covariance(Matrix_(3, 3,
|
|
|
|
sx*sx, 0.0, 0.0,
|
|
|
|
0.0, sy*sy, 0.0,
|
|
|
|
0.0, 0.0, st*st
|
|
|
|
)));
|
2010-01-10 21:55:55 +08:00
|
|
|
|
2010-01-02 18:33:33 +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
|
|
|
// Very simple test establishing Ax-b \approx z-h(x)
|
2010-01-10 21:55:55 +08:00
|
|
|
TEST( Pose2Factor, error )
|
2009-12-10 01:29:43 +08:00
|
|
|
{
|
2010-01-10 21:55:55 +08:00
|
|
|
// Choose a linearization point
|
|
|
|
Pose2 p1; // robot at origin
|
|
|
|
Pose2 p2(1, 0, 0); // robot at (1,0)
|
|
|
|
Pose2Config x0;
|
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
|
|
|
x0.insert(1, p1);
|
|
|
|
x0.insert(2, p2);
|
2010-01-10 21:55:55 +08:00
|
|
|
|
|
|
|
// Create factor
|
|
|
|
Pose2 z = between(p1,p2);
|
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
|
|
|
Pose2Factor factor(1, 2, z, covariance);
|
2010-01-10 21:55:55 +08:00
|
|
|
|
|
|
|
// Actual linearization
|
|
|
|
boost::shared_ptr<GaussianFactor> linear = factor.linearize(x0);
|
|
|
|
|
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
|
|
|
// Check error at x0, i.e. delta = zero !
|
2010-01-10 21:55:55 +08:00
|
|
|
VectorConfig delta;
|
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
|
|
|
delta.insert("x1", zero(3));
|
|
|
|
delta.insert("x2", zero(3));
|
2010-01-10 21:55:55 +08:00
|
|
|
Vector error_at_zero = Vector_(3,0.0,0.0,0.0);
|
2010-01-18 13:38:53 +08:00
|
|
|
CHECK(assert_equal(error_at_zero,factor.unwhitenedError(x0)));
|
2010-01-10 21:55:55 +08:00
|
|
|
CHECK(assert_equal(-error_at_zero,linear->error_vector(delta)));
|
|
|
|
|
|
|
|
// Check error after increasing p2
|
2010-02-17 11:29:12 +08:00
|
|
|
VectorConfig plus = delta;
|
|
|
|
plus.insertAdd("x2", Vector_(3, 0.1, 0.0, 0.0));
|
2010-01-10 21:55:55 +08:00
|
|
|
Pose2Config x1 = expmap(x0, plus);
|
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
|
|
|
Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 !
|
2010-01-18 13:38:53 +08:00
|
|
|
CHECK(assert_equal(error_at_plus,factor.whitenedError(x1)));
|
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
|
|
|
CHECK(assert_equal(error_at_plus,linear->error_vector(plus)));
|
2010-01-10 21:55:55 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// common Pose2Factor for tests below
|
|
|
|
static Pose2 measured(2,2,M_PI_2);
|
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
|
|
|
static Pose2Factor factor(1,2,measured, covariance);
|
2009-12-10 01:29:43 +08:00
|
|
|
|
2010-01-10 21:55:55 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2Factor, rhs )
|
|
|
|
{
|
2009-12-10 01:29:43 +08:00
|
|
|
// Choose a linearization point
|
|
|
|
Pose2 p1(1.1,2,M_PI_2); // robot at (1.1,2) looking towards y (ground truth is at 1,2, see testPose2)
|
2010-01-10 21:55:55 +08:00
|
|
|
Pose2 p2(-1,4.1,M_PI); // robot at (-1,4.1) looking at negative (ground truth is at -1,4)
|
|
|
|
Pose2Config x0;
|
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
|
|
|
x0.insert(1,p1);
|
|
|
|
x0.insert(2,p2);
|
2010-01-10 21:55:55 +08:00
|
|
|
|
|
|
|
// Actual linearization
|
|
|
|
boost::shared_ptr<GaussianFactor> linear = factor.linearize(x0);
|
|
|
|
|
|
|
|
// Check RHS
|
|
|
|
Pose2 hx0 = between(p1,p2);
|
|
|
|
CHECK(assert_equal(Pose2(2.1, 2.1, M_PI_2),hx0));
|
|
|
|
Vector expected_b = Vector_(3, -0.1/sx, 0.1/sy, 0.0);
|
2010-01-18 13:38:53 +08:00
|
|
|
CHECK(assert_equal(expected_b,-factor.whitenedError(x0)));
|
2010-01-10 21:55:55 +08:00
|
|
|
CHECK(assert_equal(expected_b,linear->get_b()));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// The error |A*dx-b| approximates (h(x0+dx)-z) = -error_vector
|
|
|
|
// Hence i.e., b = approximates z-h(x0) = error_vector(x0)
|
|
|
|
Vector h(const Pose2& p1,const Pose2& p2) {
|
2010-01-18 13:38:53 +08:00
|
|
|
return covariance->whiten(factor.evaluateError(p1,p2));
|
2010-01-10 21:55:55 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2Factor, linearize )
|
|
|
|
{
|
|
|
|
// Choose a linearization point at ground truth
|
|
|
|
Pose2 p1(1,2,M_PI_2);
|
|
|
|
Pose2 p2(-1,4,M_PI);
|
|
|
|
Pose2Config x0;
|
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
|
|
|
x0.insert(1,p1);
|
|
|
|
x0.insert(2,p2);
|
2009-12-10 01:29:43 +08:00
|
|
|
|
2010-01-02 18:33:33 +08:00
|
|
|
// expected linearization
|
2010-01-18 13:38:53 +08:00
|
|
|
Matrix expectedH1 = covariance->Whiten(Matrix_(3,3,
|
2010-01-10 21:55:55 +08:00
|
|
|
0.0,-1.0,-2.0,
|
|
|
|
1.0, 0.0,-2.0,
|
2009-12-22 00:43:23 +08:00
|
|
|
0.0, 0.0,-1.0
|
2010-01-18 13:38:53 +08:00
|
|
|
));
|
|
|
|
Matrix expectedH2 = covariance->Whiten(Matrix_(3,3,
|
2009-12-22 00:43:23 +08:00
|
|
|
1.0, 0.0, 0.0,
|
|
|
|
0.0, 1.0, 0.0,
|
|
|
|
0.0, 0.0, 1.0
|
2010-01-18 13:38:53 +08:00
|
|
|
));
|
2010-01-10 21:55:55 +08:00
|
|
|
Vector expected_b = Vector_(3, 0.0, 0.0, 0.0);
|
|
|
|
|
|
|
|
// expected linear factor
|
2010-01-23 01:36:57 +08:00
|
|
|
SharedDiagonal probModel1 = noiseModel::Unit::Create(3);
|
2010-01-21 02:32:48 +08:00
|
|
|
GaussianFactor expected("x1", expectedH1, "x2", expectedH2, expected_b, probModel1);
|
2009-12-10 01:29:43 +08:00
|
|
|
|
2010-01-02 18:33:33 +08:00
|
|
|
// Actual linearization
|
2010-01-10 21:55:55 +08:00
|
|
|
boost::shared_ptr<GaussianFactor> actual = factor.linearize(x0);
|
2009-12-10 01:29:43 +08:00
|
|
|
CHECK(assert_equal(expected,*actual));
|
2010-01-10 21:55:55 +08:00
|
|
|
|
|
|
|
// Numerical do not work out because BetweenFactor is approximate ?
|
|
|
|
Matrix numericalH1 = numericalDerivative21(h, p1, p2, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,numericalH1));
|
|
|
|
Matrix numericalH2 = numericalDerivative22(h, p1, p2, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH2,numericalH2));
|
2009-12-10 01:29:43 +08:00
|
|
|
}
|
2009-12-10 07:43:01 +08:00
|
|
|
|
2009-12-10 01:29:43 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|