2014-12-05 22:28:10 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
* All Rights Reserved
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
|
|
|
/**
|
|
|
|
* @file testSimilarity3.cpp
|
|
|
|
* @brief Unit tests for Similarity3 class
|
|
|
|
*/
|
|
|
|
|
2015-02-19 14:21:20 +08:00
|
|
|
#include <gtsam_unstable/geometry/Similarity3.h>
|
2015-01-13 01:58:17 +08:00
|
|
|
#include <gtsam/inference/Symbol.h>
|
|
|
|
#include <gtsam/slam/PriorFactor.h>
|
2015-01-29 03:55:13 +08:00
|
|
|
#include <gtsam/slam/BetweenFactor.h>
|
2015-01-13 01:58:17 +08:00
|
|
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
|
|
|
#include <gtsam/nonlinear/Values.h>
|
|
|
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
2015-01-07 22:57:48 +08:00
|
|
|
|
2014-12-12 23:12:58 +08:00
|
|
|
#include <gtsam/base/Testable.h>
|
2014-12-05 22:28:10 +08:00
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
|
|
|
|
|
|
using namespace gtsam;
|
|
|
|
using namespace std;
|
2015-01-29 03:55:13 +08:00
|
|
|
using symbol_shorthand::X;
|
2014-12-05 22:28:10 +08:00
|
|
|
|
2015-01-25 11:42:48 +08:00
|
|
|
GTSAM_CONCEPT_TESTABLE_INST(Similarity3)
|
2015-01-23 21:10:21 +08:00
|
|
|
|
2015-01-07 22:57:48 +08:00
|
|
|
static Point3 P(0.2,0.7,-2);
|
|
|
|
static Rot3 R = Rot3::rodriguez(0.3,0,0);
|
|
|
|
static Similarity3 T(R,Point3(3.5,-8.2,4.2),1);
|
|
|
|
static Similarity3 T2(Rot3::rodriguez(0.3,0.2,0.1),Point3(3.5,-8.2,4.2),1);
|
|
|
|
static Similarity3 T3(Rot3::rodriguez(-90, 0, 0), Point3(1, 2, 3), 1);
|
|
|
|
|
2014-12-05 22:28:10 +08:00
|
|
|
//******************************************************************************
|
2014-12-12 23:12:58 +08:00
|
|
|
TEST(Similarity3, Constructors) {
|
|
|
|
Similarity3 test;
|
|
|
|
}
|
|
|
|
|
|
|
|
//******************************************************************************
|
|
|
|
TEST(Similarity3, Getters) {
|
2014-12-05 22:28:10 +08:00
|
|
|
Similarity3 test;
|
2014-12-12 23:12:58 +08:00
|
|
|
EXPECT(assert_equal(Rot3(), test.rotation()));
|
|
|
|
EXPECT(assert_equal(Point3(), test.translation()));
|
|
|
|
EXPECT_DOUBLES_EQUAL(1.0, test.scale(), 1e-9);
|
|
|
|
}
|
|
|
|
|
|
|
|
//******************************************************************************
|
|
|
|
TEST(Similarity3, Getters2) {
|
|
|
|
Similarity3 test(Rot3::ypr(1, 2, 3), Point3(4, 5, 6), 7);
|
|
|
|
EXPECT(assert_equal(Rot3::ypr(1, 2, 3), test.rotation()));
|
|
|
|
EXPECT(assert_equal(Point3(4, 5, 6), test.translation()));
|
|
|
|
EXPECT_DOUBLES_EQUAL(7.0, test.scale(), 1e-9);
|
2014-12-05 22:28:10 +08:00
|
|
|
}
|
|
|
|
|
2015-01-25 14:28:16 +08:00
|
|
|
TEST(Similarity3, AdjointMap) {
|
|
|
|
Similarity3 test(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7);
|
|
|
|
Matrix7 result;
|
|
|
|
result << -1.5739, -2.4512, -6.3651, -50.7671, -11.2503, 16.8859, -28.0000,
|
|
|
|
6.3167, -2.9884, -0.4111, 0.8502, 8.6373, -49.7260, -35.0000,
|
|
|
|
-2.5734, -5.8362, 2.8839, 33.1363, 0.3024, 30.1811, -42.0000,
|
|
|
|
0, 0, 0, -0.2248, -0.3502, -0.9093, 0,
|
|
|
|
0, 0, 0, 0.9024, -0.4269, -0.0587, 0,
|
|
|
|
0, 0, 0, -0.3676, -0.8337, 0.4120, 0,
|
|
|
|
0, 0, 0, 0, 0, 0, 1.0000;
|
|
|
|
EXPECT(assert_equal(result, test.AdjointMap(), 1e-3));
|
|
|
|
}
|
|
|
|
|
2015-01-27 02:38:32 +08:00
|
|
|
TEST(Similarity3, inverse) {
|
|
|
|
Similarity3 test(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7);
|
|
|
|
Matrix3 Re;
|
|
|
|
Re << -0.2248, 0.9024, -0.3676,
|
|
|
|
-0.3502, -0.4269, -0.8337,
|
|
|
|
-0.9093, -0.0587, 0.4120;
|
|
|
|
Vector3 te(-9.8472, 59.7640, 10.2125);
|
|
|
|
Similarity3 expected(Re, te, 1.0/7.0);
|
|
|
|
EXPECT(assert_equal(expected, test.inverse(), 1e-3));
|
|
|
|
}
|
|
|
|
|
|
|
|
TEST(Similarity3, multiplication) {
|
|
|
|
Similarity3 test1(Rot3::ypr(1,2,3).inverse(), Point3(4,5,6), 7);
|
|
|
|
Similarity3 test2(Rot3::ypr(1,2,3).inverse(), Point3(8,9,10), 11);
|
|
|
|
Matrix3 re;
|
|
|
|
re << 0.0688, 0.9863, -0.1496,
|
|
|
|
-0.5665, -0.0848, -0.8197,
|
|
|
|
-0.8211, 0.1412, 0.5530;
|
|
|
|
Vector3 te(-13.6797, 3.2441, -5.7794);
|
|
|
|
Similarity3 expected(re, te, 77);
|
|
|
|
EXPECT(assert_equal(expected, test1*test2, 1e-2));
|
|
|
|
}
|
|
|
|
|
2014-12-05 22:28:10 +08:00
|
|
|
//******************************************************************************
|
2014-12-12 23:12:58 +08:00
|
|
|
TEST(Similarity3, Manifold) {
|
2014-12-05 22:28:10 +08:00
|
|
|
EXPECT_LONGS_EQUAL(7, Similarity3::Dim());
|
2014-12-12 23:12:58 +08:00
|
|
|
Vector z = Vector7::Zero();
|
2014-12-05 22:28:10 +08:00
|
|
|
Similarity3 sim;
|
2014-12-12 23:12:58 +08:00
|
|
|
EXPECT(sim.retract(z) == sim);
|
2014-12-05 22:28:10 +08:00
|
|
|
|
|
|
|
Vector7 v = Vector7::Zero();
|
|
|
|
v(6) = 2;
|
2014-12-05 22:50:09 +08:00
|
|
|
Similarity3 sim2;
|
2014-12-12 23:12:58 +08:00
|
|
|
EXPECT(sim2.retract(z) == sim2);
|
2014-12-05 22:28:10 +08:00
|
|
|
|
2014-12-12 23:12:58 +08:00
|
|
|
EXPECT(assert_equal(z, sim2.localCoordinates(sim)));
|
2014-12-12 11:54:02 +08:00
|
|
|
|
2015-01-13 01:58:17 +08:00
|
|
|
Similarity3 sim3 = Similarity3(Rot3(), Point3(1, 2, 3), 1);
|
2014-12-12 23:12:58 +08:00
|
|
|
Vector v3(7);
|
2015-01-02 22:02:43 +08:00
|
|
|
v3 << 0, 0, 0, 1, 2, 3, 0;
|
2014-12-12 23:12:58 +08:00
|
|
|
EXPECT(assert_equal(v3, sim2.localCoordinates(sim3)));
|
2014-12-12 11:54:02 +08:00
|
|
|
|
2015-01-07 22:57:48 +08:00
|
|
|
// Similarity3 other = Similarity3(Rot3::ypr(0.01, 0.02, 0.03), Point3(0.4, 0.5, 0.6), 1);
|
2015-01-13 01:58:17 +08:00
|
|
|
Similarity3 other = Similarity3(Rot3::ypr(0.1, 0.2, 0.3),Point3(4,5,6),1);
|
2014-12-12 23:38:59 +08:00
|
|
|
|
2015-01-07 22:57:48 +08:00
|
|
|
Vector vlocal = sim.localCoordinates(other);
|
2015-01-02 22:02:43 +08:00
|
|
|
|
2015-01-07 22:57:48 +08:00
|
|
|
EXPECT(assert_equal(sim.retract(vlocal), other, 1e-2));
|
2014-12-12 23:38:59 +08:00
|
|
|
|
2015-01-13 01:58:17 +08:00
|
|
|
Similarity3 other2 = Similarity3(Rot3::ypr(0.3, 0, 0),Point3(4,5,6),1);
|
|
|
|
Rot3 R = Rot3::rodriguez(0.3,0,0);
|
|
|
|
|
|
|
|
Vector vlocal2 = sim.localCoordinates(other2);
|
|
|
|
|
|
|
|
EXPECT(assert_equal(sim.retract(vlocal2), other2, 1e-2));
|
|
|
|
|
2014-12-05 22:28:10 +08:00
|
|
|
// TODO add unit tests for retract and localCoordinates
|
|
|
|
}
|
|
|
|
|
2015-01-07 22:57:48 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Similarity3, retract_first_order)
|
|
|
|
{
|
|
|
|
Similarity3 id;
|
|
|
|
Vector v = zero(7);
|
|
|
|
v(0) = 0.3;
|
|
|
|
EXPECT(assert_equal(Similarity3(R, Point3(), 1), id.retract(v),1e-2));
|
|
|
|
v(3)=0.2;v(4)=0.7;v(5)=-2;
|
|
|
|
EXPECT(assert_equal(Similarity3(R, P, 1),id.retract(v),1e-2));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Similarity3, localCoordinates_first_order)
|
|
|
|
{
|
|
|
|
Vector d12 = repeat(7,0.1);
|
|
|
|
d12(6) = 1.0;
|
|
|
|
Similarity3 t1 = T, t2 = t1.retract(d12);
|
|
|
|
EXPECT(assert_equal(d12, t1.localCoordinates(t2)));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Similarity3, manifold_first_order)
|
|
|
|
{
|
|
|
|
Similarity3 t1 = T;
|
|
|
|
Similarity3 t2 = T3;
|
|
|
|
Similarity3 origin;
|
|
|
|
Vector d12 = t1.localCoordinates(t2);
|
|
|
|
EXPECT(assert_equal(t2, t1.retract(d12)));
|
|
|
|
Vector d21 = t2.localCoordinates(t1);
|
|
|
|
EXPECT(assert_equal(t1, t2.retract(d21)));
|
|
|
|
}
|
|
|
|
|
2015-01-13 01:58:17 +08:00
|
|
|
TEST(Similarity3, Optimization) {
|
|
|
|
Similarity3 prior = Similarity3(Rot3::ypr(0.1, 0.2, 0.3), Point3(1, 2, 3), 4);
|
|
|
|
noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(7, 1);
|
|
|
|
Symbol key('x',1);
|
|
|
|
PriorFactor<Similarity3> factor(key, prior, model);
|
|
|
|
|
|
|
|
NonlinearFactorGraph graph;
|
|
|
|
graph.push_back(factor);
|
|
|
|
|
|
|
|
Values initial;
|
2015-01-23 21:10:21 +08:00
|
|
|
initial.insert<Similarity3>(key, Similarity3());
|
2015-01-13 01:58:17 +08:00
|
|
|
|
2015-01-23 21:10:21 +08:00
|
|
|
Values result;
|
2015-01-27 02:38:32 +08:00
|
|
|
LevenbergMarquardtParams params;
|
|
|
|
params.setVerbosityLM("TRYCONFIG");
|
2015-01-25 11:42:48 +08:00
|
|
|
result = LevenbergMarquardtOptimizer(graph, initial).optimize();
|
2015-01-27 02:38:32 +08:00
|
|
|
EXPECT(assert_equal(prior, result.at<Similarity3>(key), 1e-4));
|
2015-01-13 01:58:17 +08:00
|
|
|
}
|
|
|
|
|
2015-01-29 03:55:13 +08:00
|
|
|
TEST(Similarity3, Optimization2) {
|
|
|
|
Similarity3 prior = Similarity3();//Rot3::ypr(0, 0, 0), Point3(1, 2, 3), 4);
|
|
|
|
Similarity3 m1 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(1.0, 0, 0), 1.0);
|
2015-02-13 22:06:08 +08:00
|
|
|
Similarity3 m2 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(0.9, 0, 0), 1.0);
|
|
|
|
Similarity3 m3 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(0.8, 0, 0), 1.0);
|
|
|
|
Similarity3 m4 = Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(0.7, 0, 0), 1.42);
|
2015-01-29 03:55:13 +08:00
|
|
|
|
|
|
|
//prior.print("Goal Transform");
|
|
|
|
noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(7, 1);
|
|
|
|
SharedDiagonal betweenNoise = noiseModel::Diagonal::Sigmas(
|
2015-02-19 14:21:20 +08:00
|
|
|
(Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1).finished());
|
|
|
|
SharedDiagonal betweenNoise2 = noiseModel::Diagonal::Sigmas(
|
|
|
|
(Vector(7) << 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.01).finished());
|
2015-01-29 03:55:13 +08:00
|
|
|
PriorFactor<Similarity3> factor(X(1), prior, model);
|
|
|
|
BetweenFactor<Similarity3> b1(X(1), X(2), m1, betweenNoise);
|
|
|
|
BetweenFactor<Similarity3> b2(X(2), X(3), m2, betweenNoise);
|
|
|
|
BetweenFactor<Similarity3> b3(X(3), X(4), m3, betweenNoise);
|
2015-02-19 14:21:20 +08:00
|
|
|
BetweenFactor<Similarity3> b4(X(4), X(1), m4, betweenNoise2);
|
2015-01-29 03:55:13 +08:00
|
|
|
|
|
|
|
|
|
|
|
NonlinearFactorGraph graph;
|
|
|
|
graph.push_back(factor);
|
|
|
|
graph.push_back(b1);
|
|
|
|
graph.push_back(b2);
|
|
|
|
graph.push_back(b3);
|
|
|
|
graph.push_back(b4);
|
|
|
|
|
|
|
|
graph.print("Full Graph");
|
|
|
|
|
|
|
|
Values initial;
|
|
|
|
initial.insert<Similarity3>(X(1), Similarity3());
|
2015-02-19 14:21:20 +08:00
|
|
|
initial.insert<Similarity3>(X(2), Similarity3(Rot3::ypr(M_PI/2.0, 0, 0), Point3(1, 0, 0), 1.1));
|
|
|
|
initial.insert<Similarity3>(X(3), Similarity3(Rot3::ypr(2.0*M_PI/2.0, 0, 0), Point3(0.9, 1.1, 0), 1.2));
|
|
|
|
initial.insert<Similarity3>(X(4), Similarity3(Rot3::ypr(3.0*M_PI/2.0, 0, 0), Point3(0, 1, 0), 1.3));
|
2015-01-29 03:55:13 +08:00
|
|
|
|
|
|
|
initial.print("Initial Estimate");
|
|
|
|
|
|
|
|
Values result;
|
|
|
|
result = LevenbergMarquardtOptimizer(graph, initial).optimize();
|
|
|
|
result.print("Optimized Estimate");
|
|
|
|
//EXPECT(assert_equal(prior, result.at<Similarity3>(key), 1e-4));
|
|
|
|
}
|
2015-01-07 22:57:48 +08:00
|
|
|
|
2014-12-05 22:28:10 +08:00
|
|
|
//******************************************************************************
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
//******************************************************************************
|
|
|
|
|