testGaussianJunctionTreeB.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 
18 #include <tests/smallExample.h>
22 #include <gtsam/geometry/Pose2.h>
24 #include <gtsam/nonlinear/Values.h>
39 #include <gtsam/inference/Symbol.h>
40 #include <gtsam/base/Matrix.h>
41 #include <gtsam/base/Testable.h>
42 
44 
45 #include <boost/shared_ptr.hpp>
46 #include <boost/tuple/tuple.hpp>
47 #include <boost/assign/std/vector.hpp>
48 
49 #include <cmath>
50 #include <list>
51 #include <utility>
52 #include <vector>
53 
54 using namespace boost::assign;
55 
56 #include <iostream>
57 
58 using namespace std;
59 using namespace gtsam;
60 using namespace example;
61 
64 
65 /* ************************************************************************* *
66  Bayes tree for smoother with "nested dissection" ordering:
67  C1 x5 x6 x4
68  C2 x3 x2 : x4
69  C3 x1 : x2
70  C4 x7 : x6
71  */
72 TEST( GaussianJunctionTreeB, constructor2 ) {
73  // create a graph
75  Values values;
76  boost::tie(nlfg, values) = createNonlinearSmoother(7);
77  SymbolicFactorGraph::shared_ptr symbolic = nlfg.symbolic();
78 
79  // linearize
81 
83  ordering += X(1), X(3), X(5), X(7), X(2), X(6), X(4);
84 
85  // create an ordering
86  GaussianEliminationTree etree(*fg, ordering);
87  SymbolicEliminationTree stree(*symbolic, ordering);
88  GaussianJunctionTree actual(etree);
89 
90  Ordering o324;
91  o324 += X(3), X(2), X(4);
92  Ordering o56;
93  o56 += X(5), X(6);
94  Ordering o7;
95  o7 += X(7);
96  Ordering o1;
97  o1 += X(1);
98 
99  // Can no longer test these:
100 // Ordering sep1;
101 // Ordering sep2; sep2 += X(4);
102 // Ordering sep3; sep3 += X(6);
103 // Ordering sep4; sep4 += X(2);
104 
105  GaussianJunctionTree::sharedNode x324 = actual.roots().front();
106  LONGS_EQUAL(2, x324->children.size());
107  GaussianJunctionTree::sharedNode x1 = x324->children.front();
108  GaussianJunctionTree::sharedNode x56 = x324->children.back();
109  if (x1->children.size() > 0)
110  x1.swap(x56); // makes it work with different tie-breakers
111 
112  LONGS_EQUAL(0, x1->children.size());
113  LONGS_EQUAL(1, x56->children.size());
114  GaussianJunctionTree::sharedNode x7 = x56->children[0];
115  LONGS_EQUAL(0, x7->children.size());
116 
117  EXPECT(assert_equal(o324, x324->orderedFrontalKeys));
118  EXPECT_LONGS_EQUAL(5, x324->factors.size());
119  EXPECT_LONGS_EQUAL(9, x324->problemSize_);
120 
121  EXPECT(assert_equal(o56, x56->orderedFrontalKeys));
122  EXPECT_LONGS_EQUAL(4, x56->factors.size());
123  EXPECT_LONGS_EQUAL(9, x56->problemSize_);
124 
125  EXPECT(assert_equal(o7, x7->orderedFrontalKeys));
126  EXPECT_LONGS_EQUAL(2, x7->factors.size());
127  EXPECT_LONGS_EQUAL(4, x7->problemSize_);
128 
129  EXPECT(assert_equal(o1, x1->orderedFrontalKeys));
130  EXPECT_LONGS_EQUAL(2, x1->factors.size());
131  EXPECT_LONGS_EQUAL(4, x1->problemSize_);
132 }
133 
135 //TEST( GaussianJunctionTreeB, optimizeMultiFrontal )
136 //{
137 // // create a graph
138 // GaussianFactorGraph fg;
139 // Ordering ordering;
140 // boost::tie(fg,ordering) = createSmoother(7);
141 //
142 // // optimize the graph
143 // GaussianJunctionTree tree(fg);
144 // VectorValues actual = tree.optimize(&EliminateQR);
145 //
146 // // verify
147 // VectorValues expected(vector<size_t>(7,2)); // expected solution
148 // Vector v = Vector2(0., 0.);
149 // for (int i=1; i<=7; i++)
150 // expected[ordering[X(i)]] = v;
151 // EXPECT(assert_equal(expected,actual));
152 //}
153 //
155 //TEST( GaussianJunctionTreeB, optimizeMultiFrontal2)
156 //{
157 // // create a graph
158 // example::Graph nlfg = createNonlinearFactorGraph();
159 // Values noisy = createNoisyValues();
160 // Ordering ordering; ordering += X(1),X(2),L(1);
161 // GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering);
162 //
163 // // optimize the graph
164 // GaussianJunctionTree tree(fg);
165 // VectorValues actual = tree.optimize(&EliminateQR);
166 //
167 // // verify
168 // VectorValues expected = createCorrectDelta(ordering); // expected solution
169 // EXPECT(assert_equal(expected,actual));
170 //}
171 //
173 //TEST(GaussianJunctionTreeB, slamlike) {
174 // Values init;
175 // NonlinearFactorGraph newfactors;
176 // NonlinearFactorGraph fullgraph;
177 // SharedDiagonal odoNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.1, 0.1, M_PI/100.0));
178 // SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0, 0.1));
179 //
180 // size_t i = 0;
181 //
182 // newfactors = NonlinearFactorGraph();
183 // newfactors.add(PriorFactor<Pose2>(X(0), Pose2(0.0, 0.0, 0.0), odoNoise));
184 // init.insert(X(0), Pose2(0.01, 0.01, 0.01));
185 // fullgraph.push_back(newfactors);
186 //
187 // for( ; i<5; ++i) {
188 // newfactors = NonlinearFactorGraph();
189 // newfactors.add(BetweenFactor<Pose2>(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise));
190 // init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
191 // fullgraph.push_back(newfactors);
192 // }
193 //
194 // newfactors = NonlinearFactorGraph();
195 // newfactors.add(BetweenFactor<Pose2>(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise));
196 // newfactors.add(BearingRangeFactor<Pose2,Point2>(X(i), L(0), Rot2::fromAngle(M_PI/4.0), 5.0, brNoise));
197 // newfactors.add(BearingRangeFactor<Pose2,Point2>(X(i), L(1), Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise));
198 // init.insert(X(i+1), Pose2(1.01, 0.01, 0.01));
199 // init.insert(L(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
200 // init.insert(L(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
201 // fullgraph.push_back(newfactors);
202 // ++ i;
203 //
204 // for( ; i<5; ++i) {
205 // newfactors = NonlinearFactorGraph();
206 // newfactors.add(BetweenFactor<Pose2>(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise));
207 // init.insert(X(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
208 // fullgraph.push_back(newfactors);
209 // }
210 //
211 // newfactors = NonlinearFactorGraph();
212 // newfactors.add(BetweenFactor<Pose2>(X(i), X(i+1), Pose2(1.0, 0.0, 0.0), odoNoise));
213 // newfactors.add(BearingRangeFactor<Pose2,Point2>(X(i), L(0), Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise));
214 // newfactors.add(BearingRangeFactor<Pose2,Point2>(X(i), L(1), Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise));
215 // init.insert(X(i+1), Pose2(6.9, 0.1, 0.01));
216 // fullgraph.push_back(newfactors);
217 // ++ i;
218 //
219 // // Compare solutions
220 // Ordering ordering = *fullgraph.orderingCOLAMD(init);
221 // GaussianFactorGraph linearized = *fullgraph.linearize(init, ordering);
222 //
223 // GaussianJunctionTree gjt(linearized);
224 // VectorValues deltaactual = gjt.optimize(&EliminateQR);
225 // Values actual = init.retract(deltaactual, ordering);
226 //
227 // GaussianBayesNet gbn = *GaussianSequentialSolver(linearized).eliminate();
228 // VectorValues delta = optimize(gbn);
229 // Values expected = init.retract(delta, ordering);
230 //
231 // EXPECT(assert_equal(expected, actual));
232 //}
233 //
235 //TEST(GaussianJunctionTreeB, simpleMarginal) {
236 //
237 // typedef BayesTree<GaussianConditional> GaussianBayesTree;
238 //
239 // // Create a simple graph
240 // NonlinearFactorGraph fg;
241 // fg.add(PriorFactor<Pose2>(X(0), Pose2(), noiseModel::Isotropic::Sigma(3, 10.0)));
242 // fg.add(BetweenFactor<Pose2>(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas(Vector3(10.0, 1.0, 1.0))));
243 //
244 // Values init;
245 // init.insert(X(0), Pose2());
246 // init.insert(X(1), Pose2(1.0, 0.0, 0.0));
247 //
248 // Ordering ordering;
249 // ordering += X(1), X(0);
250 //
251 // GaussianFactorGraph gfg = *fg.linearize(init, ordering);
252 //
253 // // Compute marginals with both sequential and multifrontal
254 // Matrix expected = GaussianSequentialSolver(gfg).marginalCovariance(1);
255 //
256 // Matrix actual1 = GaussianMultifrontalSolver(gfg).marginalCovariance(1);
257 //
258 // // Compute marginal directly from marginal factor
259 // GaussianFactor::shared_ptr marginalFactor = GaussianMultifrontalSolver(gfg).marginalFactor(1);
260 // JacobianFactor::shared_ptr marginalJacobian = boost::dynamic_pointer_cast<JacobianFactor>(marginalFactor);
261 // Matrix actual2 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin()));
262 //
263 // // Compute marginal directly from BayesTree
264 // GaussianBayesTree gbt;
265 // gbt.insert(GaussianJunctionTree(gfg).eliminate(EliminateCholesky));
266 // marginalFactor = gbt.marginalFactor(1, EliminateCholesky);
267 // marginalJacobian = boost::dynamic_pointer_cast<JacobianFactor>(marginalFactor);
268 // Matrix actual3 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin()));
269 //
270 // EXPECT(assert_equal(expected, actual1));
271 // EXPECT(assert_equal(expected, actual2));
272 // EXPECT(assert_equal(expected, actual3));
273 //}
274 
275 /* ************************************************************************* */
276 int main() {
277  TestResult tr;
278  return TestRegistry::runAllTests(tr);
279 }
280 /* ************************************************************************* */
281 
TEST(GaussianJunctionTreeB, constructor2)
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
A factor with a quadratic error function - a Gaussian.
leaf::MyValues values
MatrixXd L
Definition: LLT_example.cpp:6
Definition: Half.h:150
Factor Graph Values.
std::pair< NonlinearFactorGraph, Values > createNonlinearSmoother(int T)
Definition: smallExample.h:430
#define EXPECT(condition)
Definition: Test.h:151
Contains the HessianFactor class, a general quadratic factor.
Conditional Gaussian Base class.
Linear Factor Graph where all factors are Gaussians.
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
Bayes Tree is a tree of cliques of a Bayes Chain.
traits
Definition: chartTesting.h:28
boost::shared_ptr< SymbolicFactorGraph > symbolic() const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Pose3 x1
Definition: testPose3.cpp:588
Create small example with two poses and one landmark.
Chordal Bayes Net, the result of eliminating a factor graph.
2D Pose
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
#define X
Definition: icosphere.cpp:20
const FastVector< sharedNode > & roots() const
Definition: ClusterTree.h:160


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