First prototype, segfaults
parent
e09e24964a
commit
eef2d49e8d
|
@ -21,6 +21,7 @@
|
||||||
|
|
||||||
#include <gtsam/nonlinear/Values.h>
|
#include <gtsam/nonlinear/Values.h>
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
|
#include <gtsam/base/Testable.h>
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
#include <boost/tuple/tuple.hpp>
|
#include <boost/tuple/tuple.hpp>
|
||||||
|
|
||||||
|
@ -43,10 +44,7 @@ typedef std::map<Key, Matrix> JacobianMap;
|
||||||
*/
|
*/
|
||||||
template<int COLS>
|
template<int COLS>
|
||||||
struct CallRecord {
|
struct CallRecord {
|
||||||
|
virtual void print() const = 0;
|
||||||
/// Make sure destructor is virtual
|
|
||||||
virtual ~CallRecord() {
|
|
||||||
}
|
|
||||||
virtual void startReverseAD(JacobianMap& jacobians) const = 0;
|
virtual void startReverseAD(JacobianMap& jacobians) const = 0;
|
||||||
virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const = 0;
|
virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const = 0;
|
||||||
typedef Eigen::Matrix<double, 2, COLS> Jacobian2T;
|
typedef Eigen::Matrix<double, 2, COLS> Jacobian2T;
|
||||||
|
@ -72,15 +70,11 @@ class ExecutionTrace {
|
||||||
CallRecord<T::dimension>* ptr;
|
CallRecord<T::dimension>* ptr;
|
||||||
} content;
|
} content;
|
||||||
public:
|
public:
|
||||||
|
T value;
|
||||||
/// Pointer always starts out as a Constant
|
/// Pointer always starts out as a Constant
|
||||||
ExecutionTrace() :
|
ExecutionTrace() :
|
||||||
type(Constant) {
|
type(Constant) {
|
||||||
}
|
}
|
||||||
/// Destructor cleans up pointer if Function
|
|
||||||
~ExecutionTrace() {
|
|
||||||
if (type == Function)
|
|
||||||
delete content.ptr;
|
|
||||||
}
|
|
||||||
/// Change pointer to a Leaf Record
|
/// Change pointer to a Leaf Record
|
||||||
void setLeaf(Key key) {
|
void setLeaf(Key key) {
|
||||||
type = Leaf;
|
type = Leaf;
|
||||||
|
@ -91,6 +85,14 @@ public:
|
||||||
type = Function;
|
type = Function;
|
||||||
content.ptr = record;
|
content.ptr = record;
|
||||||
}
|
}
|
||||||
|
/// Print
|
||||||
|
virtual void print() const {
|
||||||
|
GTSAM_PRINT(value);
|
||||||
|
if (type == Leaf)
|
||||||
|
std::cout << "Leaf, key = " << content.key << std::endl;
|
||||||
|
else if (type == Function)
|
||||||
|
content.ptr->print();
|
||||||
|
}
|
||||||
/// Return record pointer, quite unsafe, used only for testing
|
/// Return record pointer, quite unsafe, used only for testing
|
||||||
template<class Record>
|
template<class Record>
|
||||||
boost::optional<Record*> record() {
|
boost::optional<Record*> record() {
|
||||||
|
@ -158,14 +160,6 @@ struct Select<2, A> {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
//template <class Derived>
|
|
||||||
//struct TypedTrace {
|
|
||||||
// virtual void startReverseAD(JacobianMap& jacobians) const = 0;
|
|
||||||
// virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const = 0;
|
|
||||||
//// template<class JacobianFT>
|
|
||||||
//// void reverseAD(const JacobianFT& dFdT, JacobianMap& jacobians) const {
|
|
||||||
//};
|
|
||||||
|
|
||||||
//-----------------------------------------------------------------------------
|
//-----------------------------------------------------------------------------
|
||||||
/**
|
/**
|
||||||
* Value and Jacobians
|
* Value and Jacobians
|
||||||
|
@ -310,8 +304,8 @@ public:
|
||||||
virtual Augmented<T> forward(const Values& values) const = 0;
|
virtual Augmented<T> forward(const Values& values) const = 0;
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values,
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
ExecutionTrace<T>& p) const = 0;
|
void* raw) const = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
//-----------------------------------------------------------------------------
|
//-----------------------------------------------------------------------------
|
||||||
|
@ -348,8 +342,11 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values, ExecutionTrace<T>& p) const {
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
return constant_;
|
void* raw) const {
|
||||||
|
ExecutionTrace<T> trace;
|
||||||
|
trace.value = constant_;
|
||||||
|
return trace;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -388,9 +385,12 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values, ExecutionTrace<T>& p) const {
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
p.setLeaf(key_);
|
void* raw) const {
|
||||||
return values.at<T>(key_);
|
ExecutionTrace<T> trace;
|
||||||
|
trace.setLeaf(key_);
|
||||||
|
trace.value = values.at<T>(key_);
|
||||||
|
return trace;
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -443,7 +443,11 @@ public:
|
||||||
struct Record: public CallRecord<T::dimension> {
|
struct Record: public CallRecord<T::dimension> {
|
||||||
ExecutionTrace<A1> trace1;
|
ExecutionTrace<A1> trace1;
|
||||||
JacobianTA dTdA1;
|
JacobianTA dTdA1;
|
||||||
|
/// print to std::cout
|
||||||
|
virtual void print() const {
|
||||||
|
std::cout << dTdA1 << std::endl;
|
||||||
|
trace1.print();
|
||||||
|
}
|
||||||
/// Start the reverse AD process
|
/// Start the reverse AD process
|
||||||
virtual void startReverseAD(JacobianMap& jacobians) const {
|
virtual void startReverseAD(JacobianMap& jacobians) const {
|
||||||
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
||||||
|
@ -461,11 +465,14 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values, ExecutionTrace<T>& p) const {
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
Record* record = new Record();
|
void* raw) const {
|
||||||
p.setFunction(record);
|
ExecutionTrace<T> trace;
|
||||||
A1 a = this->expressionA1_->traceExecution(values, record->trace1);
|
// Record* record = new Record();
|
||||||
return function_(a, record->dTdA1);
|
// p.setFunction(record);
|
||||||
|
// A1 a = this->expressionA1_->traceExecution(values, record->trace1);
|
||||||
|
// return function_(a, record->dTdA1);
|
||||||
|
return trace;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -534,7 +541,13 @@ public:
|
||||||
ExecutionTrace<A2> trace2;
|
ExecutionTrace<A2> trace2;
|
||||||
JacobianTA1 dTdA1;
|
JacobianTA1 dTdA1;
|
||||||
JacobianTA2 dTdA2;
|
JacobianTA2 dTdA2;
|
||||||
|
/// print to std::cout
|
||||||
|
virtual void print() const {
|
||||||
|
std::cout << dTdA1 << std::endl;
|
||||||
|
trace1.print();
|
||||||
|
std::cout << dTdA2 << std::endl;
|
||||||
|
trace2.print();
|
||||||
|
}
|
||||||
/// Start the reverse AD process
|
/// Start the reverse AD process
|
||||||
virtual void startReverseAD(JacobianMap& jacobians) const {
|
virtual void startReverseAD(JacobianMap& jacobians) const {
|
||||||
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
||||||
|
@ -555,12 +568,18 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values, ExecutionTrace<T>& p) const {
|
/// The raw buffer is [Record | A1 raw | A2 raw]
|
||||||
Record* record = new Record();
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
p.setFunction(record);
|
void* raw) const {
|
||||||
A1 a1 = this->expressionA1_->traceExecution(values, record->trace1);
|
ExecutionTrace<T> trace;
|
||||||
A2 a2 = this->expressionA2_->traceExecution(values, record->trace2);
|
Record* record = static_cast<Record*>(raw);
|
||||||
return function_(a1, a2, record->dTdA1, record->dTdA2);
|
trace.setFunction(record);
|
||||||
|
record->trace1 = this->expressionA1_->traceExecution(values, raw);
|
||||||
|
record->trace2 = this->expressionA2_->traceExecution(values, raw);
|
||||||
|
trace.value = function_(record->trace1.value, record->trace2.value,
|
||||||
|
record->dTdA1, record->dTdA2);
|
||||||
|
trace.print();
|
||||||
|
return trace;
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -643,7 +662,15 @@ public:
|
||||||
JacobianTA1 dTdA1;
|
JacobianTA1 dTdA1;
|
||||||
JacobianTA2 dTdA2;
|
JacobianTA2 dTdA2;
|
||||||
JacobianTA3 dTdA3;
|
JacobianTA3 dTdA3;
|
||||||
|
/// print to std::cout
|
||||||
|
virtual void print() const {
|
||||||
|
std::cout << dTdA1 << std::endl;
|
||||||
|
trace1.print();
|
||||||
|
std::cout << dTdA2 << std::endl;
|
||||||
|
trace2.print();
|
||||||
|
std::cout << dTdA3 << std::endl;
|
||||||
|
trace3.print();
|
||||||
|
}
|
||||||
/// Start the reverse AD process
|
/// Start the reverse AD process
|
||||||
virtual void startReverseAD(JacobianMap& jacobians) const {
|
virtual void startReverseAD(JacobianMap& jacobians) const {
|
||||||
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
Select<T::dimension, A1>::reverseAD(trace1, dTdA1, jacobians);
|
||||||
|
@ -667,13 +694,16 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Construct an execution trace for reverse AD
|
/// Construct an execution trace for reverse AD
|
||||||
virtual T traceExecution(const Values& values, ExecutionTrace<T>& p) const {
|
virtual ExecutionTrace<T> traceExecution(const Values& values,
|
||||||
Record* record = new Record();
|
void* raw) const {
|
||||||
p.setFunction(record);
|
ExecutionTrace<T> trace;
|
||||||
A1 a1 = this->expressionA1_->traceExecution(values, record->trace1);
|
// Record* record = new Record();
|
||||||
A2 a2 = this->expressionA2_->traceExecution(values, record->trace2);
|
// p.setFunction(record);
|
||||||
A3 a3 = this->expressionA3_->traceExecution(values, record->trace3);
|
// A1 a1 = this->expressionA1_->traceExecution(values, record->trace1);
|
||||||
return function_(a1, a2, a3, record->dTdA1, record->dTdA2, record->dTdA3);
|
// A2 a2 = this->expressionA2_->traceExecution(values, record->trace2);
|
||||||
|
// A3 a3 = this->expressionA3_->traceExecution(values, record->trace3);
|
||||||
|
// return function_(a1, a2, a3, record->dTdA1, record->dTdA2, record->dTdA3);
|
||||||
|
return trace;
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -117,9 +117,9 @@ public:
|
||||||
Augmented<T> augmented(const Values& values) const {
|
Augmented<T> augmented(const Values& values) const {
|
||||||
#define REVERSE_AD
|
#define REVERSE_AD
|
||||||
#ifdef REVERSE_AD
|
#ifdef REVERSE_AD
|
||||||
ExecutionTrace<T> trace;
|
char raw[10];
|
||||||
T value = root_->traceExecution(values, trace);
|
ExecutionTrace<T> trace = root_->traceExecution(values, raw);
|
||||||
Augmented<T> augmented(value);
|
Augmented<T> augmented(trace.value);
|
||||||
trace.startReverseAD(augmented.jacobians());
|
trace.startReverseAD(augmented.jacobians());
|
||||||
return augmented;
|
return augmented;
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -33,79 +33,79 @@ using namespace gtsam;
|
||||||
Point2 measured(-17, 30);
|
Point2 measured(-17, 30);
|
||||||
SharedNoiseModel model = noiseModel::Unit::Create(2);
|
SharedNoiseModel model = noiseModel::Unit::Create(2);
|
||||||
|
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Leaf
|
//// Leaf
|
||||||
TEST(ExpressionFactor, leaf) {
|
//TEST(ExpressionFactor, leaf) {
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(2, Point2(3, 5));
|
// values.insert(2, Point2(3, 5));
|
||||||
|
//
|
||||||
JacobianFactor expected( //
|
// JacobianFactor expected( //
|
||||||
2, (Matrix(2, 2) << 1, 0, 0, 1), //
|
// 2, (Matrix(2, 2) << 1, 0, 0, 1), //
|
||||||
(Vector(2) << -3, -5));
|
// (Vector(2) << -3, -5));
|
||||||
|
//
|
||||||
// Create leaves
|
// // Create leaves
|
||||||
Point2_ p(2);
|
// Point2_ p(2);
|
||||||
|
//
|
||||||
// Concise version
|
// // Concise version
|
||||||
ExpressionFactor<Point2> f(model, Point2(0, 0), p);
|
// ExpressionFactor<Point2> f(model, Point2(0, 0), p);
|
||||||
EXPECT_LONGS_EQUAL(2, f.dim());
|
// EXPECT_LONGS_EQUAL(2, f.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf, 1e-9));
|
// EXPECT( assert_equal(expected, *jf, 1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// non-zero noise model
|
//// non-zero noise model
|
||||||
TEST(ExpressionFactor, model) {
|
//TEST(ExpressionFactor, model) {
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(2, Point2(3, 5));
|
// values.insert(2, Point2(3, 5));
|
||||||
|
//
|
||||||
JacobianFactor expected( //
|
// JacobianFactor expected( //
|
||||||
2, (Matrix(2, 2) << 10, 0, 0, 100), //
|
// 2, (Matrix(2, 2) << 10, 0, 0, 100), //
|
||||||
(Vector(2) << -30, -500));
|
// (Vector(2) << -30, -500));
|
||||||
|
//
|
||||||
// Create leaves
|
// // Create leaves
|
||||||
Point2_ p(2);
|
// Point2_ p(2);
|
||||||
|
//
|
||||||
// Concise version
|
// // Concise version
|
||||||
SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01));
|
// SharedNoiseModel model = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.01));
|
||||||
|
//
|
||||||
ExpressionFactor<Point2> f(model, Point2(0, 0), p);
|
// ExpressionFactor<Point2> f(model, Point2(0, 0), p);
|
||||||
EXPECT_LONGS_EQUAL(2, f.dim());
|
// EXPECT_LONGS_EQUAL(2, f.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf, 1e-9));
|
// EXPECT( assert_equal(expected, *jf, 1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Unary(Leaf))
|
//// Unary(Leaf))
|
||||||
TEST(ExpressionFactor, unary) {
|
//TEST(ExpressionFactor, unary) {
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(2, Point3(0, 0, 1));
|
// values.insert(2, Point3(0, 0, 1));
|
||||||
|
//
|
||||||
JacobianFactor expected( //
|
// JacobianFactor expected( //
|
||||||
2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0), //
|
// 2, (Matrix(2, 3) << 1, 0, 0, 0, 1, 0), //
|
||||||
(Vector(2) << -17, 30));
|
// (Vector(2) << -17, 30));
|
||||||
|
//
|
||||||
// Create leaves
|
// // Create leaves
|
||||||
Point3_ p(2);
|
// Point3_ p(2);
|
||||||
|
//
|
||||||
// Concise version
|
// // Concise version
|
||||||
ExpressionFactor<Point2> f(model, measured, project(p));
|
// ExpressionFactor<Point2> f(model, measured, project(p));
|
||||||
EXPECT_LONGS_EQUAL(2, f.dim());
|
// EXPECT_LONGS_EQUAL(2, f.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf, 1e-9));
|
// EXPECT( assert_equal(expected, *jf, 1e-9));
|
||||||
}
|
//}
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
struct TestBinaryExpression {
|
struct TestBinaryExpression {
|
||||||
static Point2 myUncal(const Cal3_S2& K, const Point2& p,
|
static Point2 myUncal(const Cal3_S2& K, const Point2& p,
|
||||||
|
@ -137,236 +137,236 @@ TEST(ExpressionFactor, binary) {
|
||||||
Matrix2 expected22;
|
Matrix2 expected22;
|
||||||
expected22 << 1, 0, 0, 1;
|
expected22 << 1, 0, 0, 1;
|
||||||
|
|
||||||
// Do old trace
|
// traceRaw will fill raw with [Trace<Point2> | Binary::Record]
|
||||||
ExecutionTrace<Point2> trace;
|
EXPECT_LONGS_EQUAL(8, sizeof(double));
|
||||||
tester.binary_.traceExecution(values, trace);
|
EXPECT_LONGS_EQUAL(48, sizeof(ExecutionTrace<Point2>));
|
||||||
|
EXPECT_LONGS_EQUAL(72, sizeof(ExecutionTrace<Cal3_S2>));
|
||||||
|
EXPECT_LONGS_EQUAL(2*5*8, sizeof(Binary::JacobianTA1));
|
||||||
|
EXPECT_LONGS_EQUAL(2*2*8, sizeof(Binary::JacobianTA2));
|
||||||
|
size_t expectedRecordSize = 8 + 48 + 72 + 80 + 32; // 240
|
||||||
|
EXPECT_LONGS_EQUAL(expectedRecordSize, sizeof(Binary::Record));
|
||||||
|
size_t size = sizeof(Binary::Record);
|
||||||
|
// Use Variable Length Array, allocated on stack by gcc
|
||||||
|
// Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla
|
||||||
|
char raw[size];
|
||||||
|
ExecutionTrace<Point2> trace = tester.binary_.traceExecution(values, raw);
|
||||||
|
|
||||||
// Check matrices
|
// 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>();
|
// boost::optional<Binary::Record*> p = trace.record<Binary::Record>();
|
||||||
// CHECK(p);
|
// CHECK(p);
|
||||||
// EXPECT( assert_equal(expected25, (Matrix)(*p)->dTdA1, 1e-9));
|
// EXPECT( assert_equal(expected25, (Matrix)(*p)->dTdA1, 1e-9));
|
||||||
// EXPECT( assert_equal(expected22, (Matrix)(*p)->dTdA2, 1e-9));
|
// EXPECT( assert_equal(expected22, (Matrix)(*p)->dTdA2, 1e-9));
|
||||||
}
|
}
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Unary(Binary(Leaf,Leaf))
|
//// Unary(Binary(Leaf,Leaf))
|
||||||
TEST(ExpressionFactor, shallow) {
|
//TEST(ExpressionFactor, shallow) {
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(1, Pose3());
|
// values.insert(1, Pose3());
|
||||||
values.insert(2, Point3(0, 0, 1));
|
// values.insert(2, Point3(0, 0, 1));
|
||||||
|
//
|
||||||
// Create old-style factor to create expected value and derivatives
|
// // Create old-style factor to create expected value and derivatives
|
||||||
GenericProjectionFactor<Pose3, Point3> old(measured, model, 1, 2,
|
// GenericProjectionFactor<Pose3, Point3> old(measured, model, 1, 2,
|
||||||
boost::make_shared<Cal3_S2>());
|
// boost::make_shared<Cal3_S2>());
|
||||||
double expected_error = old.error(values);
|
// double expected_error = old.error(values);
|
||||||
GaussianFactor::shared_ptr expected = old.linearize(values);
|
// GaussianFactor::shared_ptr expected = old.linearize(values);
|
||||||
|
//
|
||||||
// Create leaves
|
// // Create leaves
|
||||||
Pose3_ x(1);
|
// Pose3_ x(1);
|
||||||
Point3_ p(2);
|
// Point3_ p(2);
|
||||||
|
//
|
||||||
// Concise version
|
// // Concise version
|
||||||
ExpressionFactor<Point2> f2(model, measured, project(transform_to(x, p)));
|
// ExpressionFactor<Point2> f2(model, measured, project(transform_to(x, p)));
|
||||||
EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
|
// EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
|
||||||
EXPECT_LONGS_EQUAL(2, f2.dim());
|
// EXPECT_LONGS_EQUAL(2, f2.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
|
||||||
EXPECT( assert_equal(*expected, *gf2, 1e-9));
|
// EXPECT( assert_equal(*expected, *gf2, 1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Binary(Leaf,Unary(Binary(Leaf,Leaf)))
|
//// Binary(Leaf,Unary(Binary(Leaf,Leaf)))
|
||||||
TEST(ExpressionFactor, tree) {
|
//TEST(ExpressionFactor, tree) {
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(1, Pose3());
|
// values.insert(1, Pose3());
|
||||||
values.insert(2, Point3(0, 0, 1));
|
// values.insert(2, Point3(0, 0, 1));
|
||||||
values.insert(3, Cal3_S2());
|
// values.insert(3, Cal3_S2());
|
||||||
|
//
|
||||||
// Create old-style factor to create expected value and derivatives
|
// // Create old-style factor to create expected value and derivatives
|
||||||
GeneralSFMFactor2<Cal3_S2> old(measured, model, 1, 2, 3);
|
// GeneralSFMFactor2<Cal3_S2> old(measured, model, 1, 2, 3);
|
||||||
double expected_error = old.error(values);
|
// double expected_error = old.error(values);
|
||||||
GaussianFactor::shared_ptr expected = old.linearize(values);
|
// GaussianFactor::shared_ptr expected = old.linearize(values);
|
||||||
|
//
|
||||||
// Create leaves
|
// // Create leaves
|
||||||
Pose3_ x(1);
|
// Pose3_ x(1);
|
||||||
Point3_ p(2);
|
// Point3_ p(2);
|
||||||
Cal3_S2_ K(3);
|
// Cal3_S2_ K(3);
|
||||||
|
//
|
||||||
// Create expression tree
|
// // Create expression tree
|
||||||
Point3_ p_cam(x, &Pose3::transform_to, p);
|
// Point3_ p_cam(x, &Pose3::transform_to, p);
|
||||||
Point2_ xy_hat(PinholeCamera<Cal3_S2>::project_to_camera, p_cam);
|
// Point2_ xy_hat(PinholeCamera<Cal3_S2>::project_to_camera, p_cam);
|
||||||
Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat);
|
// Point2_ uv_hat(K, &Cal3_S2::uncalibrate, xy_hat);
|
||||||
|
//
|
||||||
// Create factor and check value, dimension, linearization
|
// // Create factor and check value, dimension, linearization
|
||||||
ExpressionFactor<Point2> f(model, measured, uv_hat);
|
// ExpressionFactor<Point2> f(model, measured, uv_hat);
|
||||||
EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9);
|
// EXPECT_DOUBLES_EQUAL(expected_error, f.error(values), 1e-9);
|
||||||
EXPECT_LONGS_EQUAL(2, f.dim());
|
// EXPECT_LONGS_EQUAL(2, f.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
EXPECT( assert_equal(*expected, *gf, 1e-9));
|
// EXPECT( assert_equal(*expected, *gf, 1e-9));
|
||||||
|
//
|
||||||
// Concise version
|
// // Concise version
|
||||||
ExpressionFactor<Point2> f2(model, measured,
|
// ExpressionFactor<Point2> f2(model, measured,
|
||||||
uncalibrate(K, project(transform_to(x, p))));
|
// uncalibrate(K, project(transform_to(x, p))));
|
||||||
EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
|
// EXPECT_DOUBLES_EQUAL(expected_error, f2.error(values), 1e-9);
|
||||||
EXPECT_LONGS_EQUAL(2, f2.dim());
|
// EXPECT_LONGS_EQUAL(2, f2.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf2 = f2.linearize(values);
|
||||||
EXPECT( assert_equal(*expected, *gf2, 1e-9));
|
// EXPECT( assert_equal(*expected, *gf2, 1e-9));
|
||||||
|
//
|
||||||
TernaryExpression<Point2, Pose3, Point3, Cal3_S2>::Function fff = project6;
|
// TernaryExpression<Point2, Pose3, Point3, Cal3_S2>::Function fff = project6;
|
||||||
|
//
|
||||||
// Try ternary version
|
// // Try ternary version
|
||||||
ExpressionFactor<Point2> f3(model, measured, project3(x, p, K));
|
// ExpressionFactor<Point2> f3(model, measured, project3(x, p, K));
|
||||||
EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9);
|
// EXPECT_DOUBLES_EQUAL(expected_error, f3.error(values), 1e-9);
|
||||||
EXPECT_LONGS_EQUAL(2, f3.dim());
|
// EXPECT_LONGS_EQUAL(2, f3.dim());
|
||||||
boost::shared_ptr<GaussianFactor> gf3 = f3.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf3 = f3.linearize(values);
|
||||||
EXPECT( assert_equal(*expected, *gf3, 1e-9));
|
// EXPECT( assert_equal(*expected, *gf3, 1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
|
//
|
||||||
TEST(ExpressionFactor, compose1) {
|
//TEST(ExpressionFactor, compose1) {
|
||||||
|
//
|
||||||
// Create expression
|
// // Create expression
|
||||||
Rot3_ R1(1), R2(2);
|
// Rot3_ R1(1), R2(2);
|
||||||
Rot3_ R3 = R1 * R2;
|
// Rot3_ R3 = R1 * R2;
|
||||||
|
//
|
||||||
// Create factor
|
// // Create factor
|
||||||
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
// ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(1, Rot3());
|
// values.insert(1, Rot3());
|
||||||
values.insert(2, Rot3());
|
// values.insert(2, Rot3());
|
||||||
|
//
|
||||||
// Check unwhitenedError
|
// // Check unwhitenedError
|
||||||
std::vector<Matrix> H(2);
|
// std::vector<Matrix> H(2);
|
||||||
Vector actual = f.unwhitenedError(values, H);
|
// Vector actual = f.unwhitenedError(values, H);
|
||||||
EXPECT( assert_equal(eye(3), H[0],1e-9));
|
// EXPECT( assert_equal(eye(3), H[0],1e-9));
|
||||||
EXPECT( assert_equal(eye(3), H[1],1e-9));
|
// EXPECT( assert_equal(eye(3), H[1],1e-9));
|
||||||
|
//
|
||||||
// Check linearization
|
// // Check linearization
|
||||||
JacobianFactor expected(1, eye(3), 2, eye(3), zero(3));
|
// JacobianFactor expected(1, eye(3), 2, eye(3), zero(3));
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf,1e-9));
|
// EXPECT( assert_equal(expected, *jf,1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Test compose with arguments referring to the same rotation
|
//// Test compose with arguments referring to the same rotation
|
||||||
TEST(ExpressionFactor, compose2) {
|
//TEST(ExpressionFactor, compose2) {
|
||||||
|
//
|
||||||
// Create expression
|
// // Create expression
|
||||||
Rot3_ R1(1), R2(1);
|
// Rot3_ R1(1), R2(1);
|
||||||
Rot3_ R3 = R1 * R2;
|
// Rot3_ R3 = R1 * R2;
|
||||||
|
//
|
||||||
// Create factor
|
// // Create factor
|
||||||
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
// ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(1, Rot3());
|
// values.insert(1, Rot3());
|
||||||
|
//
|
||||||
// Check unwhitenedError
|
// // Check unwhitenedError
|
||||||
std::vector<Matrix> H(1);
|
// std::vector<Matrix> H(1);
|
||||||
Vector actual = f.unwhitenedError(values, H);
|
// Vector actual = f.unwhitenedError(values, H);
|
||||||
EXPECT_LONGS_EQUAL(1, H.size());
|
// EXPECT_LONGS_EQUAL(1, H.size());
|
||||||
EXPECT( assert_equal(2*eye(3), H[0],1e-9));
|
// EXPECT( assert_equal(2*eye(3), H[0],1e-9));
|
||||||
|
//
|
||||||
// Check linearization
|
// // Check linearization
|
||||||
JacobianFactor expected(1, 2 * eye(3), zero(3));
|
// JacobianFactor expected(1, 2 * eye(3), zero(3));
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf,1e-9));
|
// EXPECT( assert_equal(expected, *jf,1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Test compose with one arguments referring to a constant same rotation
|
//// Test compose with one arguments referring to a constant same rotation
|
||||||
TEST(ExpressionFactor, compose3) {
|
//TEST(ExpressionFactor, compose3) {
|
||||||
|
//
|
||||||
// Create expression
|
// // Create expression
|
||||||
Rot3_ R1(Rot3::identity()), R2(3);
|
// Rot3_ R1(Rot3::identity()), R2(3);
|
||||||
Rot3_ R3 = R1 * R2;
|
// Rot3_ R3 = R1 * R2;
|
||||||
|
//
|
||||||
// Create factor
|
// // Create factor
|
||||||
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
// ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), R3);
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(3, Rot3());
|
// values.insert(3, Rot3());
|
||||||
|
//
|
||||||
// Check unwhitenedError
|
// // Check unwhitenedError
|
||||||
std::vector<Matrix> H(1);
|
// std::vector<Matrix> H(1);
|
||||||
Vector actual = f.unwhitenedError(values, H);
|
// Vector actual = f.unwhitenedError(values, H);
|
||||||
EXPECT_LONGS_EQUAL(1, H.size());
|
// EXPECT_LONGS_EQUAL(1, H.size());
|
||||||
EXPECT( assert_equal(eye(3), H[0],1e-9));
|
// EXPECT( assert_equal(eye(3), H[0],1e-9));
|
||||||
|
//
|
||||||
// Check linearization
|
// // Check linearization
|
||||||
JacobianFactor expected(3, eye(3), zero(3));
|
// JacobianFactor expected(3, eye(3), zero(3));
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf,1e-9));
|
// EXPECT( assert_equal(expected, *jf,1e-9));
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
/* ************************************************************************* */
|
///* ************************************************************************* */
|
||||||
// Test compose with three arguments
|
//// Test compose with three arguments
|
||||||
Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3,
|
//Rot3 composeThree(const Rot3& R1, const Rot3& R2, const Rot3& R3,
|
||||||
boost::optional<Matrix3&> H1, boost::optional<Matrix3&> H2,
|
// boost::optional<Matrix3&> H1, boost::optional<Matrix3&> H2,
|
||||||
boost::optional<Matrix3&> H3) {
|
// boost::optional<Matrix3&> H3) {
|
||||||
// return dummy derivatives (not correct, but that's ok for testing here)
|
// // return dummy derivatives (not correct, but that's ok for testing here)
|
||||||
if (H1)
|
// if (H1)
|
||||||
*H1 = eye(3);
|
// *H1 = eye(3);
|
||||||
if (H2)
|
// if (H2)
|
||||||
*H2 = eye(3);
|
// *H2 = eye(3);
|
||||||
if (H3)
|
// if (H3)
|
||||||
*H3 = eye(3);
|
// *H3 = eye(3);
|
||||||
return R1 * (R2 * R3);
|
// return R1 * (R2 * R3);
|
||||||
}
|
//}
|
||||||
|
//
|
||||||
TEST(ExpressionFactor, composeTernary) {
|
//TEST(ExpressionFactor, composeTernary) {
|
||||||
|
//
|
||||||
// Create expression
|
// // Create expression
|
||||||
Rot3_ A(1), B(2), C(3);
|
// Rot3_ A(1), B(2), C(3);
|
||||||
Rot3_ ABC(composeThree, A, B, C);
|
// Rot3_ ABC(composeThree, A, B, C);
|
||||||
|
//
|
||||||
// Create factor
|
// // Create factor
|
||||||
ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), ABC);
|
// ExpressionFactor<Rot3> f(noiseModel::Unit::Create(3), Rot3(), ABC);
|
||||||
|
//
|
||||||
// Create some values
|
// // Create some values
|
||||||
Values values;
|
// Values values;
|
||||||
values.insert(1, Rot3());
|
// values.insert(1, Rot3());
|
||||||
values.insert(2, Rot3());
|
// values.insert(2, Rot3());
|
||||||
values.insert(3, Rot3());
|
// values.insert(3, Rot3());
|
||||||
|
//
|
||||||
// Check unwhitenedError
|
// // Check unwhitenedError
|
||||||
std::vector<Matrix> H(3);
|
// std::vector<Matrix> H(3);
|
||||||
Vector actual = f.unwhitenedError(values, H);
|
// Vector actual = f.unwhitenedError(values, H);
|
||||||
EXPECT_LONGS_EQUAL(3, H.size());
|
// EXPECT_LONGS_EQUAL(3, H.size());
|
||||||
EXPECT( assert_equal(eye(3), H[0],1e-9));
|
// EXPECT( assert_equal(eye(3), H[0],1e-9));
|
||||||
EXPECT( assert_equal(eye(3), H[1],1e-9));
|
// EXPECT( assert_equal(eye(3), H[1],1e-9));
|
||||||
EXPECT( assert_equal(eye(3), H[2],1e-9));
|
// EXPECT( assert_equal(eye(3), H[2],1e-9));
|
||||||
|
//
|
||||||
// Check linearization
|
// // Check linearization
|
||||||
JacobianFactor expected(1, eye(3), 2, eye(3), 3, eye(3), zero(3));
|
// JacobianFactor expected(1, eye(3), 2, eye(3), 3, eye(3), zero(3));
|
||||||
boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
// boost::shared_ptr<GaussianFactor> gf = f.linearize(values);
|
||||||
boost::shared_ptr<JacobianFactor> jf = //
|
// boost::shared_ptr<JacobianFactor> jf = //
|
||||||
boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
// boost::dynamic_pointer_cast<JacobianFactor>(gf);
|
||||||
EXPECT( assert_equal(expected, *jf,1e-9));
|
// EXPECT( assert_equal(expected, *jf,1e-9));
|
||||||
}
|
//}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
int main() {
|
int main() {
|
||||||
|
|
Loading…
Reference in New Issue