Moved ordering tests, fixed serialization and constructors, to make all inference, symbolic, and linear tests pass
parent
73fe5b2be4
commit
0e80fe6418
|
|
@ -250,7 +250,7 @@ namespace gtsam {
|
|||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_NVP(nodes_);
|
||||
ar & BOOST_SERIALIZATION_NVP(root_);
|
||||
ar & BOOST_SERIALIZATION_NVP(roots_);
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
|
|
|||
|
|
@ -152,7 +152,7 @@ namespace gtsam {
|
|||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_NVP(conditional_);
|
||||
ar & BOOST_SERIALIZATION_NVP(parent_);
|
||||
ar & BOOST_SERIALIZATION_NVP(children_);
|
||||
ar & BOOST_SERIALIZATION_NVP(children);
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
|
|
|||
|
|
@ -161,4 +161,35 @@ namespace gtsam {
|
|||
return Ordering::COLAMDConstrained(variableIndex, cmember);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void Ordering::print(const std::string& str, const KeyFormatter& keyFormatter) const
|
||||
{
|
||||
cout << str;
|
||||
// Print ordering in index order
|
||||
// Print the ordering with varsPerLine ordering entries printed on each line,
|
||||
// for compactness.
|
||||
static const size_t varsPerLine = 10;
|
||||
bool endedOnNewline = false;
|
||||
for(size_t i = 0; i < size(); ++i) {
|
||||
if(i % varsPerLine != 0)
|
||||
cout << ", ";
|
||||
cout << i << ":" << keyFormatter(at(i));
|
||||
if(i % varsPerLine == varsPerLine - 1) {
|
||||
cout << "\n";
|
||||
endedOnNewline = true;
|
||||
} else {
|
||||
endedOnNewline = false;
|
||||
}
|
||||
}
|
||||
if(!endedOnNewline)
|
||||
cout << "\n";
|
||||
cout.flush();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
bool Ordering::equals(const Ordering& other, double tol) const
|
||||
{
|
||||
return (*this) == other;
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
|||
|
|
@ -43,6 +43,8 @@ namespace gtsam {
|
|||
/// Invert (not reverse) the ordering - returns a map from key to order position
|
||||
FastMap<Key, size_t> invert() const;
|
||||
|
||||
/// @name Fill-reducing Orderings @{
|
||||
|
||||
/// Compute a fill-reducing ordering using COLAMD from a factor graph (see details for note on
|
||||
/// performance). This internally builds a VariableIndex so if you already have a VariableIndex,
|
||||
/// it is faster to use COLAMD(const VariableIndex&)
|
||||
|
|
@ -99,6 +101,14 @@ namespace gtsam {
|
|||
static GTSAM_EXPORT Ordering COLAMDConstrained(const VariableIndex& variableIndex,
|
||||
const FastMap<Key, int>& groups);
|
||||
|
||||
/// @}
|
||||
|
||||
/// @name Testable @{
|
||||
|
||||
GTSAM_EXPORT void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||
|
||||
GTSAM_EXPORT bool equals(const Ordering& other, double tol = 1e-9) const;
|
||||
|
||||
private:
|
||||
static GTSAM_EXPORT Ordering COLAMDConstrained(
|
||||
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
||||
|
|
|
|||
|
|
@ -1,118 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testInference.cpp
|
||||
* @author Richard Roberts
|
||||
* @author Alex Cunningham
|
||||
* @date Dec 6, 2010
|
||||
*/
|
||||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <gtsam/inference/inferenceOrdered.h>
|
||||
#include <gtsam/inference/VariableIndexOrdered.h>
|
||||
#include <gtsam/inference/SymbolicFactorGraphOrdered.h>
|
||||
|
||||
using namespace gtsam;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(inference, UnobservedVariables) {
|
||||
SymbolicFactorGraphOrdered sfg;
|
||||
|
||||
// Create a factor graph that skips some variables
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(1,3);
|
||||
sfg.push_factor(3,5);
|
||||
|
||||
VariableIndexOrdered variableIndex(sfg);
|
||||
|
||||
// Computes a permutation with known variables first, skipped variables last
|
||||
// Actual 0 1 3 5 2 4
|
||||
Permutation::shared_ptr actual(inference::PermutationCOLAMD(variableIndex));
|
||||
Permutation expected(6);
|
||||
expected[0] = 0;
|
||||
expected[1] = 1;
|
||||
expected[2] = 3;
|
||||
expected[3] = 5;
|
||||
expected[4] = 2;
|
||||
expected[5] = 4;
|
||||
EXPECT(assert_equal(expected, *actual));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(inference, constrained_ordering) {
|
||||
SymbolicFactorGraphOrdered sfg;
|
||||
|
||||
// create graph with wanted variable set = 2, 4
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(1,2);
|
||||
sfg.push_factor(2,3);
|
||||
sfg.push_factor(3,4);
|
||||
sfg.push_factor(4,5);
|
||||
|
||||
VariableIndexOrdered variableIndex(sfg);
|
||||
|
||||
// unconstrained version
|
||||
Permutation::shared_ptr actUnconstrained(inference::PermutationCOLAMD(variableIndex));
|
||||
Permutation expUnconstrained = Permutation::Identity(6);
|
||||
EXPECT(assert_equal(expUnconstrained, *actUnconstrained));
|
||||
|
||||
// constrained version - push one set to the end
|
||||
std::vector<int> constrainLast;
|
||||
constrainLast.push_back(2);
|
||||
constrainLast.push_back(4);
|
||||
Permutation::shared_ptr actConstrained(inference::PermutationCOLAMD(variableIndex, constrainLast));
|
||||
Permutation expConstrained(6);
|
||||
expConstrained[0] = 0;
|
||||
expConstrained[1] = 1;
|
||||
expConstrained[2] = 5;
|
||||
expConstrained[3] = 3;
|
||||
expConstrained[4] = 4;
|
||||
expConstrained[5] = 2;
|
||||
EXPECT(assert_equal(expConstrained, *actConstrained));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(inference, grouped_constrained_ordering) {
|
||||
SymbolicFactorGraphOrdered sfg;
|
||||
|
||||
// create graph with constrained groups:
|
||||
// 1: 2, 4
|
||||
// 2: 5
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(1,2);
|
||||
sfg.push_factor(2,3);
|
||||
sfg.push_factor(3,4);
|
||||
sfg.push_factor(4,5);
|
||||
|
||||
VariableIndexOrdered variableIndex(sfg);
|
||||
|
||||
// constrained version - push one set to the end
|
||||
FastMap<size_t, int> constraints;
|
||||
constraints[2] = 1;
|
||||
constraints[4] = 1;
|
||||
constraints[5] = 2;
|
||||
|
||||
Permutation::shared_ptr actConstrained(inference::PermutationCOLAMDGrouped(variableIndex, constraints));
|
||||
Permutation expConstrained(6);
|
||||
expConstrained[0] = 0;
|
||||
expConstrained[1] = 1;
|
||||
expConstrained[2] = 3;
|
||||
expConstrained[3] = 2;
|
||||
expConstrained[4] = 4;
|
||||
expConstrained[5] = 5;
|
||||
EXPECT(assert_equal(expConstrained, *actConstrained));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -0,0 +1,77 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testOrdering
|
||||
* @author Alex Cunningham
|
||||
*/
|
||||
|
||||
#include <gtsam/nonlinear/Symbol.h>
|
||||
#include <gtsam/symbolic/SymbolicFactorGraph.h>
|
||||
#include <gtsam/inference/Ordering.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <boost/assign/list_of.hpp>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace boost::assign;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(Ordering, constrained_ordering) {
|
||||
SymbolicFactorGraph sfg;
|
||||
|
||||
// create graph with wanted variable set = 2, 4
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(1,2);
|
||||
sfg.push_factor(2,3);
|
||||
sfg.push_factor(3,4);
|
||||
sfg.push_factor(4,5);
|
||||
|
||||
// unconstrained version
|
||||
Ordering actUnconstrained = Ordering::COLAMD(sfg);
|
||||
Ordering expUnconstrained = Ordering(list_of(0)(1)(2)(3)(4)(5));
|
||||
EXPECT(assert_equal(expUnconstrained, actUnconstrained));
|
||||
|
||||
// constrained version - push one set to the end
|
||||
Ordering actConstrained = Ordering::COLAMDConstrainedLast(sfg, list_of(2)(4));
|
||||
Ordering expConstrained = Ordering(list_of(0)(1)(5)(3)(4)(2));
|
||||
EXPECT(assert_equal(expConstrained, actConstrained));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(Ordering, grouped_constrained_ordering) {
|
||||
SymbolicFactorGraph sfg;
|
||||
|
||||
// create graph with constrained groups:
|
||||
// 1: 2, 4
|
||||
// 2: 5
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(1,2);
|
||||
sfg.push_factor(2,3);
|
||||
sfg.push_factor(3,4);
|
||||
sfg.push_factor(4,5);
|
||||
|
||||
// constrained version - push one set to the end
|
||||
FastMap<size_t, int> constraints;
|
||||
constraints[2] = 1;
|
||||
constraints[4] = 1;
|
||||
constraints[5] = 2;
|
||||
|
||||
Ordering actConstrained = Ordering::COLAMDConstrained(sfg, constraints);
|
||||
Ordering expConstrained = list_of(0)(1)(3)(2)(4)(5);
|
||||
EXPECT(assert_equal(expConstrained, actConstrained));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -1,88 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testSerializationInference.cpp
|
||||
* @brief
|
||||
* @author Richard Roberts
|
||||
* @date Feb 7, 2012
|
||||
*/
|
||||
|
||||
#include <gtsam/inference/IndexConditionalOrdered.h>
|
||||
#include <gtsam/inference/SymbolicFactorGraphOrdered.h>
|
||||
#include <gtsam/inference/BayesTreeOrdered.h>
|
||||
|
||||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::serializationTestHelpers;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_graph) {
|
||||
// construct expected symbolic graph
|
||||
SymbolicFactorGraphOrdered sfg;
|
||||
sfg.push_factor(0);
|
||||
sfg.push_factor(0,1);
|
||||
sfg.push_factor(0,2);
|
||||
sfg.push_factor(2,1);
|
||||
|
||||
EXPECT(equalsObj(sfg));
|
||||
EXPECT(equalsXML(sfg));
|
||||
EXPECT(equalsBinary(sfg));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_bn) {
|
||||
IndexConditionalOrdered::shared_ptr x2(new IndexConditionalOrdered(1, 2, 0));
|
||||
IndexConditionalOrdered::shared_ptr l1(new IndexConditionalOrdered(2, 0));
|
||||
IndexConditionalOrdered::shared_ptr x1(new IndexConditionalOrdered(0));
|
||||
|
||||
SymbolicBayesNetOrdered sbn;
|
||||
sbn.push_back(x2);
|
||||
sbn.push_back(l1);
|
||||
sbn.push_back(x1);
|
||||
|
||||
EXPECT(equalsObj(sbn));
|
||||
EXPECT(equalsXML(sbn));
|
||||
EXPECT(equalsBinary(sbn));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_bayes_tree ) {
|
||||
typedef BayesTreeOrdered<IndexConditionalOrdered> SymbolicBayesTree;
|
||||
static const Index _X_=0, _T_=1, _S_=2, _E_=3, _L_=4, _B_=5;
|
||||
IndexConditionalOrdered::shared_ptr
|
||||
B(new IndexConditionalOrdered(_B_)),
|
||||
L(new IndexConditionalOrdered(_L_, _B_)),
|
||||
E(new IndexConditionalOrdered(_E_, _L_, _B_)),
|
||||
S(new IndexConditionalOrdered(_S_, _L_, _B_)),
|
||||
T(new IndexConditionalOrdered(_T_, _E_, _L_)),
|
||||
X(new IndexConditionalOrdered(_X_, _E_));
|
||||
|
||||
// Bayes Tree for Asia example
|
||||
SymbolicBayesTree bayesTree;
|
||||
SymbolicBayesTree::insert(bayesTree, B);
|
||||
SymbolicBayesTree::insert(bayesTree, L);
|
||||
SymbolicBayesTree::insert(bayesTree, E);
|
||||
SymbolicBayesTree::insert(bayesTree, S);
|
||||
SymbolicBayesTree::insert(bayesTree, T);
|
||||
SymbolicBayesTree::insert(bayesTree, X);
|
||||
|
||||
EXPECT(equalsObj(bayesTree));
|
||||
EXPECT(equalsXML(bayesTree));
|
||||
EXPECT(equalsBinary(bayesTree));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -20,7 +20,7 @@
|
|||
#include <gtsam/base/TestableAssertions.h>
|
||||
|
||||
#include <gtsam/inference/VariableSlots.h>
|
||||
#include <gtsam/inference/SymbolicFactorGraphOrdered.h>
|
||||
#include <gtsam/symbolic/SymbolicFactorGraph.h>
|
||||
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
|
||||
|
|
@ -31,7 +31,7 @@ using namespace boost::assign;
|
|||
/* ************************************************************************* */
|
||||
TEST(VariableSlots, constructor) {
|
||||
|
||||
SymbolicFactorGraphOrdered fg;
|
||||
SymbolicFactorGraph fg;
|
||||
fg.push_factor(2, 3);
|
||||
fg.push_factor(0, 1);
|
||||
fg.push_factor(0, 2);
|
||||
|
|
@ -40,7 +40,7 @@ TEST(VariableSlots, constructor) {
|
|||
VariableSlots actual(fg);
|
||||
|
||||
static const size_t none = numeric_limits<size_t>::max();
|
||||
VariableSlots expected((SymbolicFactorGraphOrdered()));
|
||||
VariableSlots expected((SymbolicFactorGraph()));
|
||||
expected[0] += none, 0, 0, none;
|
||||
expected[1] += none, 1, none, none;
|
||||
expected[2] += 0, none, 1, none;
|
||||
|
|
|
|||
|
|
@ -168,6 +168,14 @@ namespace gtsam {
|
|||
VectorValues backSubstituteTranspose(const VectorValues& gx) const;
|
||||
|
||||
/// @}
|
||||
|
||||
private:
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
void serialize(ARCHIVE & ar, const unsigned int version) {
|
||||
ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
|
||||
}
|
||||
};
|
||||
|
||||
} /// namespace gtsam
|
||||
|
|
|
|||
|
|
@ -217,7 +217,7 @@ namespace gtsam {
|
|||
*/
|
||||
virtual size_t getDim(const_iterator variable) const { return info_(variable-this->begin(), 0).rows(); }
|
||||
|
||||
/** Return the number of columns and rows of the Hessian matrix */
|
||||
/** Return the number of columns and rows of the Hessian matrix, including the information vector. */
|
||||
size_t rows() const { return info_.rows(); }
|
||||
|
||||
/**
|
||||
|
|
|
|||
|
|
@ -111,28 +111,28 @@ namespace gtsam {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
//JacobianFactor::JacobianFactor(const HessianFactor& factor) {
|
||||
// keys_ = factor.keys_;
|
||||
// Ab_.assignNoalias(factor.info_);
|
||||
JacobianFactor::JacobianFactor(const HessianFactor& factor) :
|
||||
Base(factor), Ab_(VerticalBlockMatrix::LikeActiveViewOf(factor.matrixObject(), factor.rows()))
|
||||
{
|
||||
// Copy Hessian into our matrix and then do in-place Cholesky
|
||||
Ab_.full() = factor.matrixObject().full();
|
||||
|
||||
// Do Cholesky to get a Jacobian
|
||||
size_t maxrank;
|
||||
bool success;
|
||||
boost::tie(maxrank, success) = choleskyCareful(Ab_.matrix());
|
||||
|
||||
// // Do Cholesky to get a Jacobian
|
||||
// size_t maxrank;
|
||||
// bool success;
|
||||
// boost::tie(maxrank, success) = choleskyCareful(matrix_);
|
||||
// Check for indefinite system
|
||||
if(!success)
|
||||
throw IndeterminantLinearSystemException(factor.keys().front());
|
||||
|
||||
// // Check for indefinite system
|
||||
// if(!success)
|
||||
// throw IndeterminantLinearSystemException(factor.keys().front());
|
||||
|
||||
// // Zero out lower triangle
|
||||
// matrix_.topRows(maxrank).triangularView<Eigen::StrictlyLower>() =
|
||||
// Matrix::Zero(maxrank, matrix_.cols());
|
||||
// // FIXME: replace with triangular system
|
||||
// Ab_.rowEnd() = maxrank;
|
||||
// model_ = noiseModel::Unit::Create(maxrank);
|
||||
|
||||
// assertInvariants();
|
||||
//}
|
||||
// Zero out lower triangle
|
||||
Ab_.matrix().topRows(maxrank).triangularView<Eigen::StrictlyLower>() =
|
||||
Matrix::Zero(maxrank, Ab_.matrix().cols());
|
||||
// FIXME: replace with triangular system
|
||||
Ab_.rowEnd() = maxrank;
|
||||
model_ = noiseModel::Unit::Create(maxrank);
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Helper functions for combine constructor
|
||||
|
|
|
|||
|
|
@ -32,6 +32,7 @@ namespace gtsam {
|
|||
class VariableSlots;
|
||||
class GaussianFactorGraph;
|
||||
class GaussianConditional;
|
||||
class HessianFactor;
|
||||
class VectorValues;
|
||||
class Ordering;
|
||||
|
||||
|
|
@ -94,6 +95,12 @@ namespace gtsam {
|
|||
/** Convert from other GaussianFactor */
|
||||
explicit JacobianFactor(const GaussianFactor& gf);
|
||||
|
||||
/** Copy constructor */
|
||||
JacobianFactor(const JacobianFactor& jf) : Base(jf), Ab_(jf.Ab_), model_(jf.model_) {}
|
||||
|
||||
/** Conversion from HessianFactor (does Cholesky to obtain Jacobian matrix) */
|
||||
explicit JacobianFactor(const HessianFactor& hf);
|
||||
|
||||
/** default constructor for I/O */
|
||||
JacobianFactor();
|
||||
|
||||
|
|
|
|||
|
|
@ -32,8 +32,6 @@ using namespace boost::assign;
|
|||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
#define TEST TEST_UNSAFE
|
||||
|
||||
namespace {
|
||||
const Key x1=1, x2=2, x3=3, x4=4;
|
||||
const SharedDiagonal chainNoise = noiseModel::Isotropic::Sigma(1, 0.5);
|
||||
|
|
|
|||
|
|
@ -30,11 +30,11 @@ TEST(GaussianDensity, constructor)
|
|||
0., 4.6904);
|
||||
|
||||
Vector d = Vector_(2, 1.0, 2.0), s = Vector_(2, 3.0, 4.0);
|
||||
GaussianConditionalOrdered conditional(1, d, R, s);
|
||||
GaussianConditional conditional(1, d, R, noiseModel::Diagonal::Sigmas(s));
|
||||
|
||||
GaussianDensity copied(conditional);
|
||||
EXPECT(assert_equal(d, copied.get_d()));
|
||||
EXPECT(assert_equal(s, copied.get_sigmas()));
|
||||
EXPECT(assert_equal(s, copied.get_model()->sigmas()));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -124,11 +124,11 @@ TEST( KalmanFilter, linear1 ) {
|
|||
// Run iteration 3
|
||||
KalmanFilter::State p3p = kf.predict(p2, F, B, u, modelQ);
|
||||
EXPECT(assert_equal(expected3, p3p->mean()));
|
||||
LONGS_EQUAL(3, KalmanFilter::step(p3p));
|
||||
LONGS_EQUAL(3, (long)KalmanFilter::step(p3p));
|
||||
|
||||
KalmanFilter::State p3 = kf.update(p3p, H, z3, modelR);
|
||||
EXPECT(assert_equal(expected3, p3->mean()));
|
||||
LONGS_EQUAL(3, KalmanFilter::step(p3));
|
||||
LONGS_EQUAL(3, (long)KalmanFilter::step(p3));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -16,11 +16,10 @@
|
|||
* @date Feb 7, 2012
|
||||
*/
|
||||
|
||||
#include <gtsam/linear/VectorValuesOrdered.h>
|
||||
#include <gtsam/linear/JacobianFactorOrdered.h>
|
||||
#include <gtsam/linear/HessianFactorOrdered.h>
|
||||
#include <gtsam/linear/GaussianSequentialSolver.h>
|
||||
#include <gtsam/linear/GaussianISAMOrdered.h>
|
||||
#include <gtsam/linear/VectorValues.h>
|
||||
#include <gtsam/linear/JacobianFactor.h>
|
||||
#include <gtsam/linear/HessianFactor.h>
|
||||
#include <gtsam/linear/GaussianISAM.h>
|
||||
#include <gtsam/linear/NoiseModel.h>
|
||||
|
||||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
|
|
@ -130,29 +129,29 @@ TEST (Serialization, SharedDiagonal_noiseModels) {
|
|||
|
||||
/* Create GUIDs for factors */
|
||||
/* ************************************************************************* */
|
||||
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactorOrdered, "gtsam::JacobianFactor");
|
||||
BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactorOrdered , "gtsam::HessianFactor");
|
||||
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
|
||||
BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor");
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, linear_factors) {
|
||||
VectorValuesOrdered values;
|
||||
VectorValues values;
|
||||
values.insert(0, Vector_(1, 1.0));
|
||||
values.insert(1, Vector_(2, 2.0,3.0));
|
||||
values.insert(2, Vector_(2, 4.0,5.0));
|
||||
EXPECT(equalsObj<VectorValuesOrdered>(values));
|
||||
EXPECT(equalsXML<VectorValuesOrdered>(values));
|
||||
EXPECT(equalsBinary<VectorValuesOrdered>(values));
|
||||
EXPECT(equalsObj<VectorValues>(values));
|
||||
EXPECT(equalsXML<VectorValues>(values));
|
||||
EXPECT(equalsBinary<VectorValues>(values));
|
||||
|
||||
Index i1 = 4, i2 = 7;
|
||||
Matrix A1 = eye(3), A2 = -1.0 * eye(3);
|
||||
Vector b = ones(3);
|
||||
SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(3, 1.0, 2.0, 3.0));
|
||||
JacobianFactorOrdered jacobianfactor(i1, A1, i2, A2, b, model);
|
||||
JacobianFactor jacobianfactor(i1, A1, i2, A2, b, model);
|
||||
EXPECT(equalsObj(jacobianfactor));
|
||||
EXPECT(equalsXML(jacobianfactor));
|
||||
EXPECT(equalsBinary(jacobianfactor));
|
||||
|
||||
HessianFactorOrdered hessianfactor(jacobianfactor);
|
||||
HessianFactor hessianfactor(jacobianfactor);
|
||||
EXPECT(equalsObj(hessianfactor));
|
||||
EXPECT(equalsXML(hessianfactor));
|
||||
EXPECT(equalsBinary(hessianfactor));
|
||||
|
|
@ -164,7 +163,7 @@ TEST (Serialization, gaussian_conditional) {
|
|||
Matrix A2 = Matrix_(2,2, 6., 0.2, 8., 0.4);
|
||||
Matrix R = Matrix_(2,2, 0.1, 0.3, 0.0, 0.34);
|
||||
Vector d(2); d << 0.2, 0.5;
|
||||
GaussianConditionalOrdered cg(0, d, R, 1, A1, 2, A2, ones(2));
|
||||
GaussianConditional cg(0, d, R, 1, A1, 2, A2);
|
||||
|
||||
EXPECT(equalsObj(cg));
|
||||
EXPECT(equalsXML(cg));
|
||||
|
|
|
|||
|
|
@ -1,113 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testOrdering
|
||||
* @author Alex Cunningham
|
||||
*/
|
||||
|
||||
#include <gtsam/nonlinear/OrderingOrdered.h>
|
||||
#include <gtsam/nonlinear/Symbol.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( OrderingOrdered, simple_modifications ) {
|
||||
OrderingOrdered ordering;
|
||||
|
||||
// create an ordering
|
||||
Symbol x1('x', 1), x2('x', 2), x3('x', 3), x4('x', 4);
|
||||
ordering += x1, x2, x3, x4;
|
||||
|
||||
EXPECT_LONGS_EQUAL(0, ordering[x1]);
|
||||
EXPECT_LONGS_EQUAL(1, ordering[x2]);
|
||||
EXPECT_LONGS_EQUAL(2, ordering[x3]);
|
||||
EXPECT_LONGS_EQUAL(3, ordering[x4]);
|
||||
EXPECT_LONGS_EQUAL(Key(x1), ordering.key(0));
|
||||
EXPECT_LONGS_EQUAL(Key(x2), ordering.key(1));
|
||||
EXPECT_LONGS_EQUAL(Key(x3), ordering.key(2));
|
||||
EXPECT_LONGS_EQUAL(Key(x4), ordering.key(3));
|
||||
|
||||
// pop the last two elements
|
||||
OrderingOrdered::value_type x4p = ordering.pop_back();
|
||||
EXPECT_LONGS_EQUAL(3, ordering.size());
|
||||
EXPECT(assert_equal(x4, x4p.first));
|
||||
|
||||
Index x3p = ordering.pop_back().second;
|
||||
EXPECT_LONGS_EQUAL(2, ordering.size());
|
||||
EXPECT_LONGS_EQUAL(2, (int)x3p);
|
||||
|
||||
// reassemble back make the ordering 1, 2, 4, 3
|
||||
EXPECT_LONGS_EQUAL(2, ordering.push_back(x4));
|
||||
EXPECT_LONGS_EQUAL(3, ordering.push_back(x3));
|
||||
|
||||
EXPECT_LONGS_EQUAL(2, ordering[x4]);
|
||||
EXPECT_LONGS_EQUAL(3, ordering[x3]);
|
||||
|
||||
EXPECT_LONGS_EQUAL(Key(x4), ordering.key(2));
|
||||
EXPECT_LONGS_EQUAL(Key(x3), ordering.key(3));
|
||||
|
||||
// verify
|
||||
OrderingOrdered expectedFinal;
|
||||
expectedFinal += x1, x2, x4, x3;
|
||||
EXPECT(assert_equal(expectedFinal, ordering));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(OrderingOrdered, permute) {
|
||||
OrderingOrdered ordering;
|
||||
ordering += 2, 4, 6, 8;
|
||||
|
||||
OrderingOrdered expected;
|
||||
expected += 2, 8, 6, 4;
|
||||
|
||||
Permutation permutation(4);
|
||||
permutation[0] = 0;
|
||||
permutation[1] = 3;
|
||||
permutation[2] = 2;
|
||||
permutation[3] = 1;
|
||||
|
||||
OrderingOrdered actual = ordering;
|
||||
actual.permuteInPlace(permutation);
|
||||
|
||||
EXPECT(assert_equal(expected, actual));
|
||||
|
||||
EXPECT_LONGS_EQUAL(0, actual[2]);
|
||||
EXPECT_LONGS_EQUAL(1, actual[8]);
|
||||
EXPECT_LONGS_EQUAL(2, actual[6]);
|
||||
EXPECT_LONGS_EQUAL(3, actual[4]);
|
||||
EXPECT_LONGS_EQUAL(2, actual.key(0));
|
||||
EXPECT_LONGS_EQUAL(8, actual.key(1));
|
||||
EXPECT_LONGS_EQUAL(6, actual.key(2));
|
||||
EXPECT_LONGS_EQUAL(4, actual.key(3));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( OrderingOrdered, invert ) {
|
||||
// creates a map with the opposite mapping: Index->Key
|
||||
OrderingOrdered ordering;
|
||||
|
||||
// create an ordering
|
||||
Symbol x1('x', 1), x2('x', 2), x3('x', 3), x4('x', 4);
|
||||
ordering += x1, x2, x3, x4;
|
||||
|
||||
EXPECT_LONGS_EQUAL(Key(x1), ordering.key(0));
|
||||
EXPECT_LONGS_EQUAL(Key(x2), ordering.key(1));
|
||||
EXPECT_LONGS_EQUAL(Key(x3), ordering.key(2));
|
||||
EXPECT_LONGS_EQUAL(Key(x4), ordering.key(3));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
@ -0,0 +1,51 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* 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 testSerializationInference.cpp
|
||||
* @brief
|
||||
* @author Richard Roberts
|
||||
* @date Feb 7, 2012
|
||||
*/
|
||||
|
||||
#include <gtsam/symbolic/tests/symbolicExampleGraphs.h>
|
||||
|
||||
#include <gtsam/base/serializationTestHelpers.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace gtsam::serializationTestHelpers;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_graph) {
|
||||
EXPECT(equalsObj(asiaGraph));
|
||||
EXPECT(equalsXML(asiaGraph));
|
||||
EXPECT(equalsBinary(asiaGraph));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_bn) {
|
||||
EXPECT(equalsObj(asiaBayesNet));
|
||||
EXPECT(equalsXML(asiaBayesNet));
|
||||
EXPECT(equalsBinary(asiaBayesNet));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST (Serialization, symbolic_bayes_tree ) {
|
||||
EXPECT(equalsObj(asiaBayesTree));
|
||||
EXPECT(equalsXML(asiaBayesTree));
|
||||
EXPECT(equalsBinary(asiaBayesTree));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
Loading…
Reference in New Issue