2010-01-11 02:21:20 +08:00
|
|
|
/**
|
|
|
|
* @file testPose3Config.cpp
|
|
|
|
* @authors Frank Dellaert
|
|
|
|
**/
|
|
|
|
|
|
|
|
#include <iostream>
|
|
|
|
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
|
|
#include "Pose3Config.h"
|
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
using namespace gtsam;
|
|
|
|
|
|
|
|
// The world coordinate system has z pointing up, y north, x east
|
|
|
|
// The vehicle has X forward, Y right, Z down
|
|
|
|
Rot3 R1(Point3( 0, 1, 0), Point3( 1, 0, 0), Point3(0, 0, -1));
|
|
|
|
Rot3 R2(Point3(-1, 0, 0), Point3( 0, 1, 0), Point3(0, 0, -1));
|
|
|
|
Rot3 R3(Point3( 0,-1, 0), Point3(-1, 0, 0), Point3(0, 0, -1));
|
|
|
|
Rot3 R4(Point3( 1, 0, 0), Point3( 0,-1, 0), Point3(0, 0, -1));
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose3Config, pose3Circle )
|
|
|
|
{
|
|
|
|
// expected is 4 poses tangent to circle with radius 1m
|
|
|
|
Pose3Config expected;
|
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
|
|
|
expected.insert(0, Pose3(R1, Point3( 1, 0, 0)));
|
|
|
|
expected.insert(1, Pose3(R2, Point3( 0, 1, 0)));
|
|
|
|
expected.insert(2, Pose3(R3, Point3(-1, 0, 0)));
|
|
|
|
expected.insert(3, Pose3(R4, Point3( 0,-1, 0)));
|
2010-01-11 02:21:20 +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
|
|
|
Pose3Config actual = pose3Circle(4,1.0);
|
2010-01-11 02:21:20 +08:00
|
|
|
CHECK(assert_equal(expected,actual));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose3Config, expmap )
|
|
|
|
{
|
|
|
|
// expected is circle shifted to East
|
|
|
|
Pose3Config expected;
|
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
|
|
|
expected.insert(0, Pose3(R1, Point3( 1.1, 0, 0)));
|
|
|
|
expected.insert(1, Pose3(R2, Point3( 0.1, 1, 0)));
|
|
|
|
expected.insert(2, Pose3(R3, Point3(-0.9, 0, 0)));
|
|
|
|
expected.insert(3, Pose3(R4, Point3( 0.1,-1, 0)));
|
2010-01-11 02:21:20 +08:00
|
|
|
|
|
|
|
// Note expmap coordinates are in global coordinates with non-compose expmap
|
|
|
|
// so shifting to East requires little thought, different from with Pose2 !!!
|
|
|
|
Vector delta = Vector_(24,
|
|
|
|
0.0,0.0,0.0, 0.1, 0.0, 0.0,
|
|
|
|
0.0,0.0,0.0, 0.1, 0.0, 0.0,
|
|
|
|
0.0,0.0,0.0, 0.1, 0.0, 0.0,
|
|
|
|
0.0,0.0,0.0, 0.1, 0.0, 0.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
|
|
|
Pose3Config actual = expmap(pose3Circle(4,1.0),delta);
|
2010-01-11 02:21:20 +08:00
|
|
|
CHECK(assert_equal(expected,actual));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|