2010-01-10 21:55:55 +08:00
|
|
|
/**
|
|
|
|
* @file testPose2Graph.cpp
|
|
|
|
* @authors Frank Dellaert, Viorela Ila
|
|
|
|
**/
|
2009-12-11 07:45:38 +08:00
|
|
|
|
|
|
|
#include <iostream>
|
2010-01-11 02:20:10 +08:00
|
|
|
#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:20:10 +08:00
|
|
|
using namespace boost::assign;
|
2009-12-11 07:45:38 +08:00
|
|
|
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
2010-01-11 02:20:10 +08:00
|
|
|
|
2010-01-18 03:34:57 +08:00
|
|
|
#define GTSAM_MAGIC_KEY
|
|
|
|
|
2010-01-11 02:20:10 +08:00
|
|
|
#include "NonlinearOptimizer-inl.h"
|
2010-01-16 09:16:59 +08:00
|
|
|
#include "FactorGraph-inl.h"
|
2010-01-11 02:20:10 +08:00
|
|
|
#include "Ordering.h"
|
2010-01-17 02:01:16 +08:00
|
|
|
#include "pose2SLAM.h"
|
2010-01-23 08:57:54 +08:00
|
|
|
#include "Pose2SLAMOptimizer.h"
|
2009-12-11 07:45:38 +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
|
|
|
|
))), I3(noiseModel::Unit::Create(3));
|
2009-12-11 07:45:38 +08:00
|
|
|
|
2010-01-10 21:55:55 +08:00
|
|
|
/* ************************************************************************* */
|
2009-12-11 07:45:38 +08:00
|
|
|
TEST( Pose2Graph, constructor )
|
|
|
|
{
|
|
|
|
// create a factor between unknown poses p1 and p2
|
|
|
|
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
|
|
|
Pose2Factor constraint(1,2,measured, covariance);
|
2009-12-11 07:45:38 +08:00
|
|
|
Pose2Graph graph;
|
2010-01-17 03:37:17 +08:00
|
|
|
graph.addConstraint(1,2,measured, covariance);
|
2009-12-11 07:45:38 +08:00
|
|
|
// get the size of the graph
|
|
|
|
size_t actual = graph.size();
|
|
|
|
// verify
|
|
|
|
size_t expected = 1;
|
|
|
|
CHECK(actual == expected);
|
|
|
|
|
2009-12-12 03:32:46 +08:00
|
|
|
}
|
2010-01-10 21:55:55 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-01-21 02:32:48 +08:00
|
|
|
TEST( Pose2Graph, linearization )
|
2009-12-12 03:32:46 +08:00
|
|
|
{
|
|
|
|
// create a factor between unknown poses p1 and p2
|
|
|
|
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
|
|
|
Pose2Factor constraint(1,2,measured, covariance);
|
2009-12-12 03:32:46 +08:00
|
|
|
Pose2Graph graph;
|
2010-01-17 03:37:17 +08:00
|
|
|
graph.addConstraint(1,2,measured, covariance);
|
2009-12-12 03:32:46 +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)
|
|
|
|
Pose2 p2(-1,4.1,M_PI); // robot at (-1,4) looking at negative (ground truth is at 4.1,2)
|
|
|
|
Pose2Config config;
|
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
|
|
|
config.insert(1,p1);
|
|
|
|
config.insert(2,p2);
|
2009-12-12 03:32:46 +08:00
|
|
|
// Linearize
|
|
|
|
GaussianFactorGraph lfg_linearized = graph.linearize(config);
|
2009-12-12 14:18:59 +08:00
|
|
|
//lfg_linearized.print("lfg_actual");
|
2009-12-12 03:32:46 +08:00
|
|
|
|
|
|
|
// the expected linear factor
|
|
|
|
GaussianFactorGraph lfg_expected;
|
|
|
|
Matrix A1 = Matrix_(3,3,
|
2010-01-10 21:55:55 +08:00
|
|
|
0.0,-2.0, -4.2,
|
|
|
|
2.0, 0.0, -4.2,
|
|
|
|
0.0, 0.0,-10.0);
|
2009-12-12 03:32:46 +08:00
|
|
|
|
|
|
|
Matrix A2 = Matrix_(3,3,
|
2010-01-10 21:55:55 +08:00
|
|
|
2.0, 0.0, 0.0,
|
|
|
|
0.0, 2.0, 0.0,
|
|
|
|
0.0, 0.0, 10.0);
|
2009-12-12 03:32:46 +08:00
|
|
|
|
|
|
|
double sigma = 1;
|
2010-01-10 21:55:55 +08:00
|
|
|
Vector b = Vector_(3,-0.1/sx,0.1/sy,0.0);
|
2010-01-23 01:36:57 +08:00
|
|
|
SharedDiagonal probModel1 = noiseModel::Unit::Create(3);
|
2010-01-21 02:32:48 +08:00
|
|
|
lfg_expected.add("x1", A1, "x2", A2, b, probModel1);
|
2009-12-12 03:32:46 +08:00
|
|
|
|
2009-12-22 00:43:23 +08:00
|
|
|
CHECK(assert_equal(lfg_expected, lfg_linearized));
|
2009-12-11 07:45:38 +08:00
|
|
|
}
|
2010-01-10 21:55:55 +08:00
|
|
|
|
2010-01-11 02:20:10 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2Graph, optimize) {
|
|
|
|
|
|
|
|
// create a Pose graph with one equality constraint and one measurement
|
2010-01-12 04:17:28 +08:00
|
|
|
shared_ptr<Pose2Graph> fg(new Pose2Graph);
|
2010-01-17 03:37:17 +08:00
|
|
|
fg->addHardConstraint(0, Pose2(0,0,0));
|
|
|
|
fg->addConstraint(0, 1, Pose2(1,2,M_PI_2), covariance);
|
2010-01-11 02:20:10 +08:00
|
|
|
|
|
|
|
// Create initial config
|
|
|
|
boost::shared_ptr<Pose2Config> initial(new Pose2Config());
|
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(0, Pose2(0,0,0));
|
|
|
|
initial->insert(1, Pose2(0,0,0));
|
2010-01-11 02:20:10 +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";
|
2010-01-11 02:20:10 +08:00
|
|
|
typedef NonlinearOptimizer<Pose2Graph, Pose2Config> 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:20:10 +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:20:10 +08:00
|
|
|
|
|
|
|
// Check with expected config
|
|
|
|
Pose2Config 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, Pose2(0,0,0));
|
|
|
|
expected.insert(1, Pose2(1,2,M_PI_2));
|
2010-01-11 02:20:10 +08:00
|
|
|
CHECK(assert_equal(expected, *optimizer.config()));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// test optimization with 6 poses arranged in a hexagon and a loop closure
|
|
|
|
TEST(Pose2Graph, optimizeCircle) {
|
|
|
|
|
|
|
|
// Create a hexagon of poses
|
2010-01-17 02:01:16 +08:00
|
|
|
Pose2Config hexagon = pose2SLAM::circle(6,1.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
|
|
|
Pose2 p0 = hexagon[0], p1 = hexagon[1];
|
2010-01-11 02:20:10 +08:00
|
|
|
|
|
|
|
// create a Pose graph with one equality constraint and one measurement
|
2010-01-12 04:17:28 +08:00
|
|
|
shared_ptr<Pose2Graph> fg(new Pose2Graph);
|
2010-01-17 03:37:17 +08:00
|
|
|
fg->addHardConstraint(0, p0);
|
2010-01-11 02:20:10 +08:00
|
|
|
Pose2 delta = between(p0,p1);
|
2010-01-17 03:37:17 +08:00
|
|
|
fg->addConstraint(0, 1, delta, covariance);
|
|
|
|
fg->addConstraint(1,2, delta, covariance);
|
|
|
|
fg->addConstraint(2,3, delta, covariance);
|
|
|
|
fg->addConstraint(3,4, delta, covariance);
|
|
|
|
fg->addConstraint(4,5, delta, covariance);
|
|
|
|
fg->addConstraint(5, 0, delta, covariance);
|
2010-01-11 02:20:10 +08:00
|
|
|
|
|
|
|
// Create initial config
|
|
|
|
boost::shared_ptr<Pose2Config> initial(new Pose2Config());
|
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(0, p0);
|
|
|
|
initial->insert(1, expmap(hexagon[1],Vector_(3,-0.1, 0.1,-0.1)));
|
|
|
|
initial->insert(2, expmap(hexagon[2],Vector_(3, 0.1,-0.1, 0.1)));
|
|
|
|
initial->insert(3, expmap(hexagon[3],Vector_(3,-0.1, 0.1,-0.1)));
|
|
|
|
initial->insert(4, expmap(hexagon[4],Vector_(3, 0.1,-0.1, 0.1)));
|
|
|
|
initial->insert(5, expmap(hexagon[5],Vector_(3,-0.1, 0.1,-0.1)));
|
2010-01-11 02:20:10 +08:00
|
|
|
|
2010-01-23 08:57:54 +08:00
|
|
|
// Choose an ordering
|
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-23 08:57:54 +08:00
|
|
|
|
|
|
|
// optimize
|
|
|
|
pose2SLAM::Optimizer::shared_solver solver(new pose2SLAM::Optimizer::solver(ordering));
|
|
|
|
pose2SLAM::Optimizer optimizer0(fg, initial, solver);
|
|
|
|
pose2SLAM::Optimizer::verbosityLevel verbosity = pose2SLAM::Optimizer::SILENT;
|
|
|
|
pose2SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity);
|
2010-01-11 02:20:10 +08:00
|
|
|
|
|
|
|
Pose2Config actual = *optimizer.config();
|
|
|
|
|
|
|
|
// Check with ground truth
|
|
|
|
CHECK(assert_equal(hexagon, actual));
|
|
|
|
|
|
|
|
// Check loop closure
|
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(delta,between(actual[5],actual[0])));
|
2010-01-23 08:57:54 +08:00
|
|
|
|
|
|
|
// Try PCG class
|
|
|
|
// Pose2SLAMOptimizer myOptimizer("3");
|
|
|
|
|
|
|
|
// Matrix Ab1 = myOptimizer.Ab1();
|
|
|
|
// CHECK(assert_equal(Matrix_(1,1,1.0),Ab1));
|
|
|
|
//
|
|
|
|
// Matrix Ab2 = myOptimizer.Ab2();
|
|
|
|
// CHECK(assert_equal(Matrix_(1,1,1.0),Ab2));
|
|
|
|
|
|
|
|
// Here, call matlab to
|
|
|
|
// A=[A1;A2], b=[b1;b2]
|
|
|
|
// R=qr(A1)
|
|
|
|
// call pcg on A,b, with preconditioner R -> get x
|
|
|
|
|
|
|
|
// Vector x;
|
|
|
|
// myOptimizer.update(x);
|
|
|
|
|
|
|
|
// Check with ground truth
|
|
|
|
// CHECK(assert_equal(hexagon, *myOptimizer.theta()));
|
2010-01-11 02:20:10 +08:00
|
|
|
}
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2Graph, findMinimumSpanningTree) {
|
|
|
|
Pose2Graph G, T, C;
|
2010-01-18 13:38:53 +08:00
|
|
|
G.addConstraint(1, 2, Pose2(0.,0.,0.), I3);
|
|
|
|
G.addConstraint(1, 3, Pose2(0.,0.,0.), I3);
|
|
|
|
G.addConstraint(2, 3, Pose2(0.,0.,0.), I3);
|
2010-01-17 03:37:17 +08:00
|
|
|
|
|
|
|
PredecessorMap<pose2SLAM::Key> tree =
|
|
|
|
G.findMinimumSpanningTree<pose2SLAM::Key, Pose2Factor>();
|
|
|
|
CHECK(tree[1] == 1);
|
|
|
|
CHECK(tree[2] == 1);
|
|
|
|
CHECK(tree[3] == 1);
|
2010-01-16 09:16:59 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2Graph, split) {
|
|
|
|
Pose2Graph G, T, C;
|
2010-01-18 13:38:53 +08:00
|
|
|
G.addConstraint(1, 2, Pose2(0.,0.,0.), I3);
|
|
|
|
G.addConstraint(1, 3, Pose2(0.,0.,0.), I3);
|
|
|
|
G.addConstraint(2, 3, Pose2(0.,0.,0.), I3);
|
2010-01-16 09:16:59 +08:00
|
|
|
|
2010-01-17 03:37:17 +08:00
|
|
|
PredecessorMap<pose2SLAM::Key> tree;
|
|
|
|
tree.insert(1,2);
|
|
|
|
tree.insert(2,2);
|
|
|
|
tree.insert(3,2);
|
2010-01-16 09:16:59 +08:00
|
|
|
|
2010-01-17 03:37:17 +08:00
|
|
|
G.split<pose2SLAM::Key, Pose2Factor>(tree, T, C);
|
2010-01-16 09:16:59 +08:00
|
|
|
LONGS_EQUAL(2, T.size());
|
|
|
|
LONGS_EQUAL(1, C.size());
|
|
|
|
}
|
|
|
|
|
2009-12-11 07:45:38 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|