gtsam/cpp/testPose3Graph.cpp

79 lines
2.7 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 "NonlinearOptimizer-inl.h"
#include "NonlinearEquality.h"
#include "Ordering.h"
#include "Pose3Graph.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,'p');
Pose3 p0 = hexagon["p0"], p1 = hexagon["p1"];
// create a Pose graph with one equality constraint and one measurement
shared_ptr<Pose3Graph> fg(new Pose3Graph);
fg->addConstraint("p0", p0);
Pose3 delta = between(p0,p1);
fg->add("p0", "p1", delta, covariance);
fg->add("p1", "p2", delta, covariance);
fg->add("p2", "p3", delta, covariance);
fg->add("p3", "p4", delta, covariance);
fg->add("p4", "p5", delta, covariance);
fg->add("p5", "p0", delta, covariance);
// Create initial config
boost::shared_ptr<Pose3Config> initial(new Pose3Config());
initial->insert("p0", p0);
initial->insert("p1", expmap(hexagon["p1"],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1)));
initial->insert("p2", expmap(hexagon["p2"],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1)));
initial->insert("p3", expmap(hexagon["p3"],Vector_(6,-0.1, 0.1,-0.1,-0.1, 0.1,-0.1)));
initial->insert("p4", expmap(hexagon["p4"],Vector_(6, 0.1,-0.1, 0.1, 0.1,-0.1, 0.1)));
initial->insert("p5", expmap(hexagon["p5"],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 += "p0","p1","p2","p3","p4","p5";
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["p5"],actual["p0"]),1e-5));
}
/* ************************************************************************* */
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
/* ************************************************************************* */