gtsam/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp

378 lines
11 KiB
C++
Raw Normal View History

/* ----------------------------------------------------------------------------
* 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
* -------------------------------------------------------------------------- */
/**
2014-10-09 19:00:56 +08:00
* @file testExpressionFactor.cpp
* @date September 18, 2014
* @author Frank Dellaert
* @author Paul Furgale
* @brief unit tests for Block Automatic Differentiation
*/
2014-10-01 17:25:49 +08:00
#include <gtsam_unstable/slam/expressions.h>
2014-10-09 19:00:56 +08:00
#include <gtsam_unstable/nonlinear/ExpressionFactor.h>
#include <gtsam/slam/GeneralSFMFactor.h>
#include <gtsam/slam/ProjectionFactor.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
using namespace std;
using namespace gtsam;
Point2 measured(-17, 30);
SharedNoiseModel model = noiseModel::Unit::Create(2);
2014-10-08 17:06:42 +08:00
/* ************************************************************************* */
// Leaf
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, leaf) {
2014-10-08 17:06:42 +08:00
// Create some values
Values values;
values.insert(2, Point2(3, 5));
JacobianFactor expected( //
2, (Matrix(2, 2) << 1, 0, 0, 1), //
(Vector(2) << -3, -5));
// Create leaves
Point2_ p(2);
2014-10-11 14:17:46 +08:00
// Concise version
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f(model, Point2(0, 0), p);
2014-10-08 17:06:42 +08:00
EXPECT_LONGS_EQUAL(2, f.dim());
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf, 1e-9));
}
/* ************************************************************************* */
// non-zero noise model
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, model) {
2014-10-08 17:06:42 +08:00
// Create some values
Values values;
values.insert(2, Point2(3, 5));
JacobianFactor expected( //
2, (Matrix(2, 2) << 10, 0, 0, 100), //
(Vector(2) << -30, -500));
// Create leaves
Point2_ p(2);
2014-10-11 14:17:46 +08:00
// Concise version
2014-10-08 17:06:42 +08:00
SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01));
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f(model, Point2(0, 0), p);
2014-10-08 17:06:42 +08:00
EXPECT_LONGS_EQUAL(2, f.dim());
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf, 1e-9));
}
/* ************************************************************************* */
// Unary(Leaf))
2014-10-11 14:17:46 +08:00
TEST(ExpressionFactor, unary) {
// Create some values
Values values;
values.insert(2, Point3(0, 0, 1));
JacobianFactor expected( //
2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0), //
(Vector(2) << -17, 30));
// Create leaves
2014-10-01 17:01:38 +08:00
Point3_ p(2);
2014-10-01 16:53:35 +08:00
2014-10-11 14:17:46 +08:00
// Concise version
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f(model, measured, project(p));
EXPECT_LONGS_EQUAL(2, f.dim());
2014-10-03 02:28:37 +08:00
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf, 1e-9));
2014-10-03 02:28:37 +08:00
}
2014-10-11 14:17:46 +08:00
/* ************************************************************************* */
struct TestBinaryExpression {
static Point2 myUncal(const Cal3_S2& K, const Point2& p,
boost::optional<Matrix25&> Dcal, boost::optional<Matrix2&> Dp) {
return K.uncalibrate(p, Dcal, Dp);
}
Cal3_S2_ K_;
Point2_ p_;
BinaryExpression<Point2, Cal3_S2, Point2> binary_;
TestBinaryExpression() :
K_(1), p_(2), binary_(myUncal, K_, p_) {
}
};
/* ************************************************************************* */
// Binary(Leaf,Leaf)
TEST(ExpressionFactor, binary) {
2014-10-11 14:52:24 +08:00
typedef BinaryExpression<Point2, Cal3_S2, Point2> Binary;
2014-10-11 14:17:46 +08:00
TestBinaryExpression tester;
2014-10-11 14:41:39 +08:00
// Create some values
Values values;
values.insert(1, Cal3_S2());
values.insert(2, Point2(0, 0));
2014-10-11 14:52:24 +08:00
// Expected Jacobians
2014-10-11 14:41:39 +08:00
Matrix25 expected25;
expected25 << 0, 0, 0, 1, 0, 0, 0, 0, 0, 1;
Matrix2 expected22;
expected22 << 1, 0, 0, 1;
2014-10-11 14:52:24 +08:00
// Do old trace
ExecutionTrace<Point2> trace;
tester.binary_.traceExecution(values, trace);
// Check matrices
boost::optional<Binary::Record*> p = trace.record<Binary::Record>();
CHECK(p);
EXPECT( assert_equal(expected25, (Matrix)(*p)->dTdA1, 1e-9));
EXPECT( assert_equal(expected22, (Matrix)(*p)->dTdA2, 1e-9));
// // Check raw memory trace
// double raw[10];
// tester.binary_.traceRaw(values, 0);
//
// // Check matrices
// boost::optional<Binary::Record*> p = trace.record<Binary::Record>();
// CHECK(p);
// EXPECT( assert_equal(expected25, (Matrix)(*p)->dTdA1, 1e-9));
// EXPECT( assert_equal(expected22, (Matrix)(*p)->dTdA2, 1e-9));
2014-10-11 14:17:46 +08:00
}
/* ************************************************************************* */
2014-10-07 19:04:04 +08:00
// Unary(Binary(Leaf,Leaf))
2014-10-11 14:17:46 +08:00
TEST(ExpressionFactor, shallow) {
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(1, Pose3());
values.insert(2, Point3(0, 0, 1));
// Create old-style factor to create expected value and derivatives
GenericProjectionFactor<Pose3, Point3> old(measured, model, 1, 2,
boost::make_shared<Cal3_S2>());
double expected_error = old.error(values);
GaussianFactor::shared_ptr expected = old.linearize(values);
// Create leaves
Pose3_ x(1);
Point3_ p(2);
2014-10-11 14:17:46 +08:00
// Concise version
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f2(model, measured, project(transform_to(x, p)));
2014-10-07 19:04:04 +08:00
EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
EXPECT_LONGS_EQUAL(2, f2.dim());
boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
EXPECT( assert_equal(*expected, *gf2, 1e-9));
}
/* ************************************************************************* */
// Binary(Leaf,Unary(Binary(Leaf,Leaf)))
2014-10-11 14:17:46 +08:00
TEST(ExpressionFactor, tree) {
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(1, Pose3());
values.insert(2, Point3(0, 0, 1));
values.insert(3, Cal3_S2());
// Create old-style factor to create expected value and derivatives
GeneralSFMFactor2<Cal3_S2> old(measured, model, 1, 2, 3);
double expected_error = old.error(values);
GaussianFactor::shared_ptr expected = old.linearize(values);
// Create leaves
Pose3_ x(1);
Point3_ p(2);
Cal3_S2_ K(3);
// Create expression tree
Point3_ p_cam(x, &Pose3::transform_to, p);
Point2_ xy_hat(PinholeCamera<Cal3_S2>::project_to_camera, p_cam);
Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat);
// Create factor and check value, dimension, linearization
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f(model, measured, uv_hat);
2014-10-07 19:04:04 +08:00
EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9);
EXPECT_LONGS_EQUAL(2, f.dim());
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
EXPECT( assert_equal(*expected, *gf, 1e-9));
2014-10-11 14:17:46 +08:00
// Concise version
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f2(model, measured,
2014-10-07 19:04:04 +08:00
uncalibrate(K, project(transform_to(x, p))));
EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
EXPECT_LONGS_EQUAL(2, f2.dim());
boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
EXPECT( assert_equal(*expected, *gf2, 1e-9));
2014-10-07 22:11:55 +08:00
TernaryExpression<Point2, Pose3, Point3, Cal3_S2>::Function fff = project6;
2014-10-07 19:04:04 +08:00
// Try ternary version
2014-10-09 19:00:56 +08:00
ExpressionFactor<Point2> f3(model, measured, project3(x, p, K));
2014-10-07 19:04:04 +08:00
EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9);
EXPECT_LONGS_EQUAL(2, f3.dim());
boost::shared_ptr<GaussianFactor> gf3 = f3.linearize(values);
EXPECT( assert_equal(*expected, *gf3, 1e-9));
}
/* ************************************************************************* */
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, compose1) {
2014-10-07 19:04:04 +08:00
// Create expression
Rot3_ R1(1), R2(2);
Rot3_ R3 = R1 * R2;
// Create factor
2014-10-09 19:00:56 +08:00
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(1, Rot3());
values.insert(2, Rot3());
// Check unwhitenedError
std::vector<Matrix> H(2);
Vector actual = f.unwhitenedError(values, H);
EXPECT( assert_equal(eye(3), H[0],1e-9));
EXPECT( assert_equal(eye(3), H[1],1e-9));
// Check linearization
JacobianFactor expected(1, eye(3), 2, eye(3), zero(3));
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf,1e-9));
}
/* ************************************************************************* */
// Test compose with arguments referring to the same rotation
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, compose2) {
2014-10-07 19:04:04 +08:00
// Create expression
Rot3_ R1(1), R2(1);
Rot3_ R3 = R1 * R2;
// Create factor
2014-10-09 19:00:56 +08:00
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(1, Rot3());
// Check unwhitenedError
std::vector<Matrix> H(1);
Vector actual = f.unwhitenedError(values, H);
EXPECT_LONGS_EQUAL(1, H.size());
EXPECT( assert_equal(2*eye(3), H[0],1e-9));
// Check linearization
JacobianFactor expected(1, 2 * eye(3), zero(3));
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf,1e-9));
}
/* ************************************************************************* */
// Test compose with one arguments referring to a constant same rotation
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, compose3) {
2014-10-07 19:04:04 +08:00
// Create expression
Rot3_ R1(Rot3::identity()), R2(3);
Rot3_ R3 = R1 * R2;
// Create factor
2014-10-09 19:00:56 +08:00
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(3, Rot3());
// Check unwhitenedError
std::vector<Matrix> H(1);
Vector actual = f.unwhitenedError(values, H);
EXPECT_LONGS_EQUAL(1, H.size());
EXPECT( assert_equal(eye(3), H[0],1e-9));
// Check linearization
JacobianFactor expected(3, eye(3), zero(3));
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf,1e-9));
}
/* ************************************************************************* */
// Test compose with three arguments
Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3,
boost::optional<Matrix3&> H1, boost::optional<Matrix3&> H2,
boost::optional<Matrix3&> H3) {
// return dummy derivatives (not correct, but that's ok for testing here)
if (H1)
*H1 = eye(3);
if (H2)
*H2 = eye(3);
if (H3)
*H3 = eye(3);
return R1 * (R2 * R3);
}
2014-10-09 19:00:56 +08:00
TEST(ExpressionFactor, composeTernary) {
2014-10-07 19:04:04 +08:00
// Create expression
Rot3_ A(1), B(2), C(3);
Rot3_ ABC(composeThree, A, B, C);
// Create factor
2014-10-09 19:00:56 +08:00
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), ABC);
2014-10-07 19:04:04 +08:00
// Create some values
Values values;
values.insert(1, Rot3());
values.insert(2, Rot3());
values.insert(3, Rot3());
// Check unwhitenedError
std::vector<Matrix> H(3);
Vector actual = f.unwhitenedError(values, H);
EXPECT_LONGS_EQUAL(3, H.size());
EXPECT( assert_equal(eye(3), H[0],1e-9));
EXPECT( assert_equal(eye(3), H[1],1e-9));
EXPECT( assert_equal(eye(3), H[2],1e-9));
// Check linearization
JacobianFactor expected(1, eye(3), 2, eye(3), 3, eye(3), zero(3));
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
boost::shared_ptr<JacobianFactor> jf = //
boost::dynamic_pointer_cast<JacobianFactor>(gf);
EXPECT( assert_equal(expected, *jf,1e-9));
}
/* ************************************************************************* */
int main() {
TestResult tr;
return TestRegistry::runAllTests(tr);
}
/* ************************************************************************* */