29 #include <boost/assign/list_of.hpp> 30 #include <boost/assign/std/list.hpp> 37 using namespace gtsam;
41 if (get<0>(a) == get<0>(b) && get<1>(a) == get<1>(b) &&
42 get<2>(a) == get<2>(b))
return true;
44 cout <<
"not equal:" << endl;
45 cout <<
"\texpected: " 46 "(" << get<0>(
a) <<
", " << get<1>(a) <<
") = " << get<2>(
a) << endl;
48 "(" << get<0>(
b) <<
", " << get<1>(b) <<
") = " << get<2>(
b) << endl;
70 1., 2., 1., 2., 3., 4., 3., 4., 3., 4., 5., 6., 5., 6., 6., 7., 8., 7., 8., 7., 8.,
71 1., 2., 7., 7., 1., 2., 3., 4., 7., 7., 1., 2., 5., 6., 7., 3., 4., 5., 6., 7., 7.,
72 10., 10., -1., -1., -10., -10., 10., 10., 2., -1., -5., -5., 5., 5.,
73 1., -5., -5., 5., 5., -1., 1.5).finished();
104 4., 6.,32.).finished();
107 Matrix expectedMatlab = expected.transpose();
111 const Key x123 = 0, x45 = 1;
112 gfg.
add(x123, (
Matrix(2, 3) << 1, 2, 3, 5, 6, 7).finished(),
114 gfg.
add(x123, (
Matrix(2, 3) << 9, 10, 0, 0, 0, 0).finished(),
115 x45, (
Matrix(2, 2) << 11, 12, 14, 15.).finished(),
127 for (
int i = 0;
i < 16;
i++) {
143 Matrix A00 = (
Matrix(2, 3) << 1, 2, 3, 5, 6, 7).finished();
144 Matrix A10 = (
Matrix(2, 3) << 9, 10, 0, 0, 0, 0).finished();
150 gfg.
add(0, A10, 1, A11,
Vector2(13., 16.), model);
153 Ab << 1, 2, 3, 0, 0, 4, 5, 6, 7, 0, 0, 8, 9, 10, 0, 11, 12, 13, 0, 0, 0, 14, 15, 16;
160 Matrix A = Ab.leftCols(Ab.cols() - 1);
161 Vector b = Ab.col(Ab.cols() - 1);
164 boost::tie(actualA, actualb) = gfg.
jacobian();
170 Vector eta = A.transpose() *
b;
173 boost::tie(actualL, actualeta) = gfg.
hessian();
179 expectLdiagonal.
insert(0,
Vector3(1 + 25 + 81, 4 + 36 + 100, 9 + 49));
197 fg +=
JacobianFactor(x1, 10 * I_2x2, -1.0 * Vector::Ones(2), unit2);
274 boost::tie(AtA, eta) = gfg.
hessian();
278 expectedAtA << 125, 0, -25, 0, -100, 0,
279 0, 125, 0, -25, 0, -100,
280 -25, 0, 50, 0, -25, 0,
281 0, -25, 0, 50, 0, -25,
282 -100, 0, -25, 0, 225, 0,
283 0, -100, 0, -25, 0, 225;
294 expected.insert(0,
Vector2(-450, -450));
295 expected.insert(1,
Vector2(0, 0));
296 expected.insert(2,
Vector2(950, 1050));
311 400*I_2x2,
Vector2(1.0, 1.0), 3.0);
322 boost::tie(AtA, eta) = gfg.
hessian();
324 X << 1, 2, 3, 4, 5, 6;
326 Y << -450, -450, 300, 400, 2950, 3450;
332 expected.insert(0,
Vector2(-450, -450));
333 expected.insert(1,
Vector2(300, 400));
334 expected.insert(2,
Vector2(2950, 3450));
353 boost::tie(AtA, eta) = gfg.
hessian();
375 blockMatrix.
matrix() << 1.0, 0.0, 2.0, 0.0, 3.0, 0.0, 0.1, 0.0, 1.0, 0.0, 2.0, 0.0, 3.0, 0.2, 0.0,
376 0.0, 3.0, 0.0, 4.0, 0.0, 0.3, 0.0, 0.0, 0.0, 3.0, 0.0, 4.0, 0.4;
395 jacFactor0->getA(jacFactor0->begin()) *= 7.;
420 Vector d = infoMatrix.diagonal();
423 expected.
insert(0, d.segment<2>(0));
424 expected.
insert(1, d.segment<2>(2));
425 expected.
insert(2, d.segment<2>(4));
virtual std::map< Key, Matrix > hessianBlockDiagonal() const
Provides additional testing facilities for common data structures.
#define EQUALITY(expected, actual)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
bool triplet_equal(SparseTriplet a, SparseTriplet b)
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static GaussianFactorGraph createGaussianFactorGraphWithHessianFactor()
const Matrix & matrix() const
EIGEN_DONT_INLINE Scalar zero()
A matrix with column blocks of pre-defined sizes. Used in JacobianFactor and GaussianConditional.
Matrix sparseJacobian_() const
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
boost::shared_ptr< This > shared_ptr
static GaussianFactorGraph createSimpleGaussianFactorGraph()
Factor graph with 2 2D factors on 3 2D variables.
Matrix augmentedJacobian(const Ordering &ordering) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
VariableSlots describes the structure of a combined factor in terms of where each block comes from in...
void add(const GaussianFactor &factor)
VectorValues transposeMultiply(const Errors &e) const
std::tuple< size_t, size_t, double > SparseTriplet
VectorValues gradient(const VectorValues &x0) const
#define EXPECT(condition)
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > eliminatePartialSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
Matrix augmentedHessian(const Ordering &ordering) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Conditional Gaussian Base class.
Linear Factor Graph where all factors are Gaussians.
std::vector< std::tuple< int, int, double > > sparseJacobian(const Ordering &ordering, size_t &nrows, size_t &ncols) const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
std::pair< Matrix, Vector > jacobian(const Ordering &ordering) const
#define LONGS_EQUAL(expected, actual)
std::pair< Matrix, Vector > hessian(const Ordering &ordering) const
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
noiseModel::Diagonal::shared_ptr SharedDiagonal
TEST(GaussianFactorGraph, initialization)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
const sharedFactor at(size_t i) const
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const
#define EXPECT_LONGS_EQUAL(expected, actual)
virtual GaussianFactorGraph clone() const
VectorValues optimizeDensely() const
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
A Gaussian factor using the canonical parameters (information form)
Chordal Bayes Net, the result of eliminating a factor graph.
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
virtual VectorValues hessianDiagonal() const
std::uint64_t Key
Integer nonlinear key type.
GaussianFactorGraph negate() const
virtual VectorValues gradientAtZero() const