testGaussianFactorGraph.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
26 #include <gtsam/base/debug.h>
28 
29 #include <boost/assign/list_of.hpp>
30 #include <boost/assign/std/list.hpp> // for operator +=
31 using namespace boost::assign;
32 
35 
36 using namespace std;
37 using namespace gtsam;
38 
39 typedef std::tuple<size_t, size_t, double> SparseTriplet;
41  if (get<0>(a) == get<0>(b) && get<1>(a) == get<1>(b) &&
42  get<2>(a) == get<2>(b)) return true;
43 
44  cout << "not equal:" << endl;
45  cout << "\texpected: "
46  "(" << get<0>(a) << ", " << get<1>(a) << ") = " << get<2>(a) << endl;
47  cout << "\tactual: "
48  "(" << get<0>(b) << ", " << get<1>(b) << ") = " << get<2>(b) << endl;
49  return false;
50 }
51 
52 /* ************************************************************************* */
54  // Create empty graph
56  SharedDiagonal unit2 = noiseModel::Unit::Create(2);
57 
58  fg +=
59  JacobianFactor(0, 10*I_2x2, -1.0*Vector::Ones(2), unit2),
60  JacobianFactor(0, -10*I_2x2,1, 10*I_2x2, Vector2(2.0, -1.0), unit2),
61  JacobianFactor(0, -5*I_2x2, 2, 5*I_2x2, Vector2(0.0, 1.0), unit2),
62  JacobianFactor(1, -5*I_2x2, 2, 5*I_2x2, Vector2(-1.0, 1.5), unit2);
63 
64  EXPECT_LONGS_EQUAL(4, (long)fg.size());
65 
66  // Test sparse, which takes a vector and returns a matrix, used in MATLAB
67  // Note that this the augmented vector and the RHS is in column 7
68  Matrix expectedIJS =
69  (Matrix(3, 21) <<
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();
74  Matrix actualIJS = fg.sparseJacobian_();
75  EQUALITY(expectedIJS, actualIJS);
76 }
77 
78 /* ************************************************************************* */
79 TEST(GaussianFactorGraph, sparseJacobian) {
80  // Create factor graph:
81  // x1 x2 x3 x4 x5 b
82  // 1 2 3 0 0 4
83  // 5 6 7 0 0 8
84  // 9 10 0 11 12 13
85  // 0 0 0 14 15 16
86 
87  // Expected
88  Matrix expected = (Matrix(16, 3) <<
89  1., 1., 2.,
90  1., 2., 4.,
91  1., 3., 6.,
92  2., 1.,10.,
93  2., 2.,12.,
94  2., 3.,14.,
95  1., 6., 8.,
96  2., 6.,16.,
97  3., 1.,18.,
98  3., 2.,20.,
99  3., 4.,22.,
100  3., 5.,24.,
101  4., 4.,28.,
102  4., 5.,30.,
103  3., 6.,26.,
104  4., 6.,32.).finished();
105 
106  // expected: in matlab format - NOTE the transpose!)
107  Matrix expectedMatlab = expected.transpose();
108 
110  SharedDiagonal model = noiseModel::Isotropic::Sigma(2, 0.5);
111  const Key x123 = 0, x45 = 1;
112  gfg.add(x123, (Matrix(2, 3) << 1, 2, 3, 5, 6, 7).finished(),
113  Vector2(4, 8), model);
114  gfg.add(x123, (Matrix(2, 3) << 9, 10, 0, 0, 0, 0).finished(),
115  x45, (Matrix(2, 2) << 11, 12, 14, 15.).finished(),
116  Vector2(13, 16), model);
117 
118  Matrix actual = gfg.sparseJacobian_();
119 
120  EXPECT(assert_equal(expectedMatlab, actual));
121 
122  // SparseTriplets
123  auto boostActual = gfg.sparseJacobian();
124  // check the triplets size...
125  EXPECT_LONGS_EQUAL(16, boostActual.size());
126  // check content
127  for (int i = 0; i < 16; i++) {
129  SparseTriplet(expected(i, 0) - 1, expected(i, 1) - 1, expected(i, 2)),
130  boostActual.at(i)));
131  }
132 }
133 
134 /* ************************************************************************* */
136  // Create factor graph:
137  // x1 x2 x3 x4 x5 b
138  // 1 2 3 0 0 4
139  // 5 6 7 0 0 8
140  // 9 10 0 11 12 13
141  // 0 0 0 14 15 16
142 
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();
145  Matrix A11 = (Matrix(2, 2) << 11, 12, 14, 15).finished();
146 
148  SharedDiagonal model = noiseModel::Unit::Create(2);
149  gfg.add(0, A00, Vector2(4., 8.), model);
150  gfg.add(0, A10, 1, A11, Vector2(13., 16.), model);
151 
152  Matrix Ab(4, 6);
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;
154 
155  // augmented versions
157  EXPECT(assert_equal(Ab.transpose() * Ab, gfg.augmentedHessian()));
158 
159  // jacobian
160  Matrix A = Ab.leftCols(Ab.cols() - 1);
161  Vector b = Ab.col(Ab.cols() - 1);
162  Matrix actualA;
163  Vector actualb;
164  boost::tie(actualA, actualb) = gfg.jacobian();
165  EXPECT(assert_equal(A, actualA));
166  EXPECT(assert_equal(b, actualb));
167 
168  // hessian
169  Matrix L = A.transpose() * A;
170  Vector eta = A.transpose() * b;
171  Matrix actualL;
172  Vector actualeta;
173  boost::tie(actualL, actualeta) = gfg.hessian();
174  EXPECT(assert_equal(L, actualL));
175  EXPECT(assert_equal(eta, actualeta));
176 
177  // hessianBlockDiagonal
178  VectorValues expectLdiagonal; // Make explicit that diagonal is sum-squares of columns
179  expectLdiagonal.insert(0, Vector3(1 + 25 + 81, 4 + 36 + 100, 9 + 49));
180  expectLdiagonal.insert(1, Vector2(121 + 196, 144 + 225));
181  EXPECT(assert_equal(expectLdiagonal, gfg.hessianDiagonal()));
182 
183  // hessianBlockDiagonal
184  map<Key, Matrix> actualBD = gfg.hessianBlockDiagonal();
185  LONGS_EQUAL(2, actualBD.size());
186  EXPECT(assert_equal(A00.transpose() * A00 + A10.transpose() * A10, actualBD[0]));
187  EXPECT(assert_equal(A11.transpose() * A11, actualBD[1]));
188 }
189 
190 /* ************************************************************************* */
194  Key x1 = 2, x2 = 0, l1 = 1;
195  SharedDiagonal unit2 = noiseModel::Unit::Create(2);
196  // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_]
197  fg += JacobianFactor(x1, 10 * I_2x2, -1.0 * Vector::Ones(2), unit2);
198  // odometry between x1 and x2: x2-x1=[0.2;-0.1]
199  fg += JacobianFactor(x2, 10 * I_2x2, x1, -10 * I_2x2, Vector2(2.0, -1.0), unit2);
200  // measurement between x1 and l1: l1-x1=[0.0;0.2]
201  fg += JacobianFactor(l1, 5 * I_2x2, x1, -5 * I_2x2, Vector2(0.0, 1.0), unit2);
202  // measurement between x2 and l1: l1-x2=[-0.2;0.3]
203  fg += JacobianFactor(x2, -5 * I_2x2, l1, 5 * I_2x2, Vector2(-1.0, 1.5), unit2);
204  return fg;
205 }
206 
207 /* ************************************************************************* */
210 
211  // Construct expected gradient
212  // 2*f(x) = 100*(x1+c[X(1)])^2 + 100*(x2-x1-[0.2;-0.1])^2 + 25*(l1-x1-[0.0;0.2])^2 +
213  // 25*(l1-x2-[-0.2;0.3])^2
214  // worked out: df/dx1 = 100*[0.1;0.1] + 100*[0.2;-0.1]) + 25*[0.0;0.2] = [10+20;10-10+5] = [30;5]
215  VectorValues expected = map_list_of<Key, Vector>(1, Vector2(5.0, -12.5))(2, Vector2(30.0, 5.0))(
216  0, Vector2(-25.0, 17.5));
217 
218  // Check the gradient at delta=0
219  VectorValues zero = VectorValues::Zero(expected);
220  VectorValues actual = fg.gradient(zero);
221  EXPECT(assert_equal(expected, actual));
222  EXPECT(assert_equal(expected, fg.gradientAtZero()));
223 
224  // Check the gradient at the solution (should be zero)
225  VectorValues solution = fg.optimize();
226  VectorValues actual2 = fg.gradient(solution);
227  EXPECT(assert_equal(VectorValues::Zero(solution), actual2));
228 }
229 
230 /* ************************************************************************* */
231 TEST(GaussianFactorGraph, transposeMultiplication) {
233 
234  Errors e;
235  e += Vector2(0.0, 0.0), Vector2(15.0, 0.0), Vector2(0.0, -5.0), Vector2(-7.5, -5.0);
236 
238  expected.insert(1, Vector2(-37.5, -50.0));
239  expected.insert(2, Vector2(-150.0, 25.0));
240  expected.insert(0, Vector2(187.5, 25.0));
241 
242  VectorValues actual = A.transposeMultiply(e);
243  EXPECT(assert_equal(expected, actual));
244 }
245 
246 /* ************************************************************************* */
247 TEST(GaussianFactorGraph, eliminate_empty) {
248  // eliminate an empty factor
250  gfg.add(JacobianFactor());
252  GaussianFactorGraph::shared_ptr remainingGFG;
253  boost::tie(actualBN, remainingGFG) = gfg.eliminatePartialSequential(Ordering());
254 
255  // expected Bayes net is empty
256  GaussianBayesNet expectedBN;
257 
258  // expected remaining graph should be the same as the original, still containing the empty factor
259  GaussianFactorGraph expectedLF = gfg;
260 
261  // check if the result matches
262  EXPECT(assert_equal(*actualBN, expectedBN));
263  EXPECT(assert_equal(*remainingGFG, expectedLF));
264 }
265 
266 /* ************************************************************************* */
269  Matrix A;
270  Vector b;
271  boost::tie(A, b) = gfg.jacobian();
272  Matrix AtA;
273  Vector eta;
274  boost::tie(AtA, eta) = gfg.hessian();
275  EXPECT(assert_equal(A.transpose() * A, AtA));
276  EXPECT(assert_equal(A.transpose() * b, eta));
277  Matrix expectedAtA(6, 6);
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;
284  EXPECT(assert_equal(expectedAtA, AtA));
285 }
286 
287 /* ************************************************************************* */
288 TEST(GaussianFactorGraph, multiplyHessianAdd) {
290 
291  VectorValues x = map_list_of<Key, Vector>(0, Vector2(1, 2))(1, Vector2(3, 4))(2, Vector2(5, 6));
292 
294  expected.insert(0, Vector2(-450, -450));
295  expected.insert(1, Vector2(0, 0));
296  expected.insert(2, Vector2(950, 1050));
297 
298  VectorValues actual;
299  gfg.multiplyHessianAdd(1.0, x, actual);
300  EXPECT(assert_equal(expected, actual));
301 
302  // now, do it with non-zero y
303  gfg.multiplyHessianAdd(1.0, x, actual);
304  EXPECT(assert_equal(2 * expected, actual));
305 }
306 
307 /* ************************************************************************* */
310  gfg += HessianFactor(1, 2, 100*I_2x2, Z_2x2, Vector2(0.0, 1.0),
311  400*I_2x2, Vector2(1.0, 1.0), 3.0);
312  return gfg;
313 }
314 
315 /* ************************************************************************* */
316 TEST(GaussianFactorGraph, multiplyHessianAdd2) {
318 
319  // brute force
320  Matrix AtA;
321  Vector eta;
322  boost::tie(AtA, eta) = gfg.hessian();
323  Vector X(6);
324  X << 1, 2, 3, 4, 5, 6;
325  Vector Y(6);
326  Y << -450, -450, 300, 400, 2950, 3450;
327  EXPECT(assert_equal(Y, AtA * X));
328 
329  VectorValues x = map_list_of<Key, Vector>(0, Vector2(1, 2))(1, Vector2(3, 4))(2, Vector2(5, 6));
330 
332  expected.insert(0, Vector2(-450, -450));
333  expected.insert(1, Vector2(300, 400));
334  expected.insert(2, Vector2(2950, 3450));
335 
336  VectorValues actual;
337  gfg.multiplyHessianAdd(1.0, x, actual);
338  EXPECT(assert_equal(expected, actual));
339 
340  // now, do it with non-zero y
341  gfg.multiplyHessianAdd(1.0, x, actual);
342  EXPECT(assert_equal(2 * expected, actual));
343 }
344 
345 /* ************************************************************************* */
346 TEST(GaussianFactorGraph, matricesMixed) {
348  Matrix A;
349  Vector b;
350  boost::tie(A, b) = gfg.jacobian(); // incorrect !
351  Matrix AtA;
352  Vector eta;
353  boost::tie(AtA, eta) = gfg.hessian(); // correct
354  EXPECT(assert_equal(A.transpose() * A, AtA));
355  Vector expected = -(Vector(6) << -25, 17.5, 5, -13.5, 29, 4).finished();
356  EXPECT(assert_equal(expected, eta));
357  EXPECT(assert_equal(A.transpose() * b, eta));
358 }
359 
360 /* ************************************************************************* */
361 TEST(GaussianFactorGraph, gradientAtZero) {
364  VectorValues actual = gfg.gradientAtZero();
365  expected.insert(0, Vector2(-25, 17.5));
366  expected.insert(1, Vector2(5, -13.5));
367  expected.insert(2, Vector2(29, 4));
368  EXPECT(assert_equal(expected, actual));
369 }
370 
371 /* ************************************************************************* */
373  // 2 variables, frontal has dim=4
374  VerticalBlockMatrix blockMatrix(list_of(4)(2)(1), 4);
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;
377  GaussianConditional cg(list_of(1)(2), 1, blockMatrix);
378 
380  init_graph.push_back(GaussianFactor::shared_ptr());
381  init_graph.push_back(GaussianConditional(cg));
382 
383  GaussianFactorGraph exp_graph =
384  createGaussianFactorGraphWithHessianFactor(); // Created separately
386  exp_graph.push_back(GaussianConditional(cg));
387 
388  GaussianFactorGraph actCloned = init_graph.clone();
389  EXPECT(assert_equal(init_graph, actCloned)); // Same as the original version
390 
391  // Apply an in-place change to init_graph and compare
392  JacobianFactor::shared_ptr jacFactor0 =
393  boost::dynamic_pointer_cast<JacobianFactor>(init_graph.at(0));
394  CHECK(jacFactor0);
395  jacFactor0->getA(jacFactor0->begin()) *= 7.;
396  EXPECT(assert_inequal(init_graph, exp_graph));
397  EXPECT(assert_equal(exp_graph, actCloned));
398 }
399 
400 /* ************************************************************************* */
403  init_graph.push_back(GaussianFactor::shared_ptr());
404  GaussianFactorGraph actNegation = init_graph.negate();
405  GaussianFactorGraph expNegation;
406  expNegation.push_back(init_graph.at(0)->negate());
407  expNegation.push_back(init_graph.at(1)->negate());
408  expNegation.push_back(init_graph.at(2)->negate());
409  expNegation.push_back(init_graph.at(3)->negate());
410  expNegation.push_back(init_graph.at(4)->negate());
411  expNegation.push_back(GaussianFactor::shared_ptr());
412  EXPECT(assert_equal(expNegation, actNegation));
413 }
414 
415 /* ************************************************************************* */
416 TEST(GaussianFactorGraph, hessianDiagonal) {
419  Matrix infoMatrix = gfg.hessian().first;
420  Vector d = infoMatrix.diagonal();
421 
422  VectorValues actual = gfg.hessianDiagonal();
423  expected.insert(0, d.segment<2>(0));
424  expected.insert(1, d.segment<2>(2));
425  expected.insert(2, d.segment<2>(4));
426  EXPECT(assert_equal(expected, actual));
427 }
428 
429 TEST(GaussianFactorGraph, DenseSolve) {
432  VectorValues actual = fg.optimizeDensely();
433  EXPECT(assert_equal(expected, actual));
434 }
435 
436 /* ************************************************************************* */
437 int main() {
438  TestResult tr;
439  return TestRegistry::runAllTests(tr);
440 }
441 /* ************************************************************************* */
virtual std::map< Key, Matrix > hessianBlockDiagonal() const
Provides additional testing facilities for common data structures.
size_t size() const
Definition: FactorGraph.h:306
#define CHECK(condition)
Definition: Test.h:109
#define EQUALITY(expected, actual)
Definition: Test.h:128
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Scalar * b
Definition: benchVecAdd.cpp:17
bool triplet_equal(SparseTriplet a, SparseTriplet b)
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Global debugging flags.
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static GaussianFactorGraph createGaussianFactorGraphWithHessianFactor()
const Matrix & matrix() const
EIGEN_DONT_INLINE Scalar zero()
Definition: svd_common.h:271
A matrix with column blocks of pre-defined sizes. Used in JacobianFactor and GaussianConditional.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
MatrixXd L
Definition: LLT_example.cpp:6
Definition: Half.h:150
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.
Definition: FactorGraph.h:166
Array33i a
VariableSlots describes the structure of a combined factor in terms of where each block comes from in...
T negate(const T &x)
Definition: packetmath.cpp:27
void add(const GaussianFactor &factor)
VectorValues transposeMultiply(const Errors &e) const
Eigen::VectorXd Vector
Definition: Vector.h:38
std::tuple< size_t, size_t, double > SparseTriplet
VectorValues gradient(const VectorValues &x0) const
#define EXPECT(condition)
Definition: Test.h:151
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)
Definition: Test.h:135
std::pair< Matrix, Vector > hessian(const Ordering &ordering) const
gtsam::Key l1
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
TEST(GaussianFactorGraph, initialization)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:315
Eigen::Vector2d Vector2
Definition: Vector.h:42
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
virtual GaussianFactorGraph clone() const
VectorValues optimizeDensely() const
Pose3 x1
Definition: testPose3.cpp:588
bool assert_inequal(const Matrix &A, const Matrix &B, double tol)
Definition: Matrix.cpp:62
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
#define X
Definition: icosphere.cpp:20
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.
Definition: types.h:61
GaussianFactorGraph negate() const
virtual VectorValues gradientAtZero() const


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:42