2010-01-16 09:16:59 +08:00
|
|
|
/**
|
|
|
|
* @file testPlanarSLAM.cpp
|
|
|
|
* @authors Frank Dellaert
|
|
|
|
**/
|
|
|
|
|
|
|
|
#include <iostream>
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
2010-01-18 13:38:53 +08:00
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
#include "planarSLAM.h"
|
2010-04-02 06:02:31 +08:00
|
|
|
#include "BearingRangeFactor.h"
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
using namespace gtsam;
|
|
|
|
|
|
|
|
// some shared test values
|
2010-01-18 13:38:53 +08:00
|
|
|
static Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI_4);
|
|
|
|
static Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3);
|
|
|
|
|
2010-01-23 01:36:57 +08:00
|
|
|
SharedGaussian
|
2010-01-18 13:38:53 +08:00
|
|
|
sigma(noiseModel::Isotropic::Sigma(1,0.1)),
|
2010-04-02 06:02:31 +08:00
|
|
|
sigma2(noiseModel::Isotropic::Sigma(2,0.1)),
|
2010-01-18 13:38:53 +08:00
|
|
|
I3(noiseModel::Unit::Create(3));
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( planarSLAM, BearingFactor )
|
|
|
|
{
|
|
|
|
// Create factor
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
Rot2 z = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1
|
2010-01-16 09:16:59 +08:00
|
|
|
planarSLAM::Bearing factor(2, 3, z, sigma);
|
|
|
|
|
|
|
|
// create config
|
|
|
|
planarSLAM::Config c;
|
|
|
|
c.insert(2, x2);
|
|
|
|
c.insert(3, l3);
|
|
|
|
|
|
|
|
// Check error
|
2010-01-18 13:38:53 +08:00
|
|
|
Vector actual = factor.unwhitenedError(c);
|
2010-01-16 09:16:59 +08:00
|
|
|
CHECK(assert_equal(Vector_(1,-0.1),actual));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( planarSLAM, RangeFactor )
|
|
|
|
{
|
|
|
|
// Create factor
|
|
|
|
double z(sqrt(2) - 0.22); // h(x) - z = 0.22
|
|
|
|
planarSLAM::Range factor(2, 3, z, sigma);
|
|
|
|
|
|
|
|
// create config
|
|
|
|
planarSLAM::Config c;
|
|
|
|
c.insert(2, x2);
|
|
|
|
c.insert(3, l3);
|
|
|
|
|
|
|
|
// Check error
|
2010-01-18 13:38:53 +08:00
|
|
|
Vector actual = factor.unwhitenedError(c);
|
2010-01-16 09:16:59 +08:00
|
|
|
CHECK(assert_equal(Vector_(1,0.22),actual));
|
|
|
|
}
|
|
|
|
|
2010-04-02 06:02:31 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( planarSLAM, BearingRangeFactor )
|
|
|
|
{
|
|
|
|
// Create factor
|
|
|
|
Rot2 r = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1
|
|
|
|
double b(sqrt(2) - 0.22); // h(x) - z = 0.22
|
2010-04-03 11:36:10 +08:00
|
|
|
planarSLAM::BearingRange factor(2, 3, r, b, sigma2);
|
2010-04-02 06:02:31 +08:00
|
|
|
|
|
|
|
// create config
|
|
|
|
planarSLAM::Config c;
|
|
|
|
c.insert(2, x2);
|
|
|
|
c.insert(3, l3);
|
|
|
|
|
|
|
|
// Check error
|
|
|
|
Vector actual = factor.unwhitenedError(c);
|
|
|
|
CHECK(assert_equal(Vector_(2,-0.1, 0.22),actual));
|
|
|
|
}
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( planarSLAM, constructor )
|
|
|
|
{
|
|
|
|
// create config
|
|
|
|
planarSLAM::Config c;
|
|
|
|
c.insert(2, x2);
|
|
|
|
c.insert(3, x3);
|
|
|
|
c.insert(3, l3);
|
|
|
|
|
|
|
|
// create graph
|
|
|
|
planarSLAM::Graph G;
|
|
|
|
|
|
|
|
// Add pose constraint
|
|
|
|
G.addPoseConstraint(2, x2); // make it feasible :-)
|
|
|
|
|
|
|
|
// Add odometry
|
2010-01-18 13:38:53 +08:00
|
|
|
G.addOdometry(2, 3, Pose2(0, 0, M_PI_4), I3);
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// Create bearing factor
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
Rot2 z1 = Rot2::fromAngle(M_PI_4 + 0.1); // h(x) - z = -0.1
|
2010-01-18 13:38:53 +08:00
|
|
|
G.addBearing(2, 3, z1, sigma);
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// Create range factor
|
|
|
|
double z2(sqrt(2) - 0.22); // h(x) - z = 0.22
|
2010-01-18 13:38:53 +08:00
|
|
|
G.addRange(2, 3, z2, sigma);
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
Vector expected = Vector_(8, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1, 0.22);
|
2010-01-18 13:38:53 +08:00
|
|
|
CHECK(assert_equal(expected,G.unwhitenedError(c)));
|
2010-01-16 09:16:59 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|