79 lines
2.6 KiB
C++
79 lines
2.6 KiB
C++
/**
|
|
* @file testPose3Graph.cpp
|
|
* @authors Frank Dellaert, Viorela Ila
|
|
**/
|
|
|
|
#include <iostream>
|
|
|
|
#include <iostream>
|
|
#include <boost/shared_ptr.hpp>
|
|
#include <boost/assign/std/list.hpp>
|
|
using namespace boost;
|
|
using namespace boost::assign;
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
|
|
#include "Pose3Graph.h"
|
|
#include "NonlinearOptimizer-inl.h"
|
|
#include "NonlinearEquality.h"
|
|
#include "Ordering.h"
|
|
|
|
using namespace std;
|
|
using namespace gtsam;
|
|
|
|
// common measurement covariance
|
|
static Matrix covariance = eye(6);
|
|
|
|
/* ************************************************************************* */
|
|
// test optimization with 6 poses arranged in a hexagon and a loop closure
|
|
TEST(Pose3Graph, optimizeCircle) {
|
|
|
|
// Create a hexagon of poses
|
|
Pose3Config hexagon = pose3Circle(6,1.0);
|
|
Pose3 p0 = hexagon[0], p1 = hexagon[1];
|
|
|
|
// create a Pose graph with one equality constraint and one measurement
|
|
shared_ptr<Pose3Graph> fg(new Pose3Graph);
|
|
fg->addConstraint(0, p0);
|
|
Pose3 delta = between(p0,p1);
|
|
fg->add(0,1, delta, covariance);
|
|
fg->add(1,2, delta, covariance);
|
|
fg->add(2,3, delta, covariance);
|
|
fg->add(3,4, delta, covariance);
|
|
fg->add(4,5, delta, covariance);
|
|
fg->add(5,0, delta, covariance);
|
|
|
|
// Create initial config
|
|
boost::shared_ptr<Pose3Config> initial(new Pose3Config());
|
|
initial->insert(0, p0);
|
|
initial->insert(1, expmap(hexagon[1],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1)));
|
|
initial->insert(2, expmap(hexagon[2],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1)));
|
|
initial->insert(3, expmap(hexagon[3],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1)));
|
|
initial->insert(4, expmap(hexagon[4],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1)));
|
|
initial->insert(5, expmap(hexagon[5],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1)));
|
|
|
|
// Choose an ordering and optimize
|
|
shared_ptr<Ordering> ordering(new Ordering);
|
|
*ordering += "x0","x1","x2","x3","x4","x5";
|
|
typedef NonlinearOptimizer<Pose3Graph, Pose3Config> Optimizer;
|
|
Optimizer optimizer0(fg, ordering, initial);
|
|
Optimizer::verbosityLevel verbosity = Optimizer::SILENT;
|
|
// Optimizer::verbosityLevel verbosity = Optimizer::ERROR;
|
|
Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity);
|
|
|
|
Pose3Config actual = *optimizer.config();
|
|
|
|
// Check with ground truth
|
|
CHECK(assert_equal(hexagon, actual,1e-5));
|
|
|
|
// Check loop closure
|
|
CHECK(assert_equal(delta,between(actual[5],actual[0]),1e-5));
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
int main() {
|
|
TestResult tr;
|
|
return TestRegistry::runAllTests(tr);
|
|
}
|
|
/* ************************************************************************* */
|