testDiscreteFactorGraph.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 
12 /*
13  * @file testDiscreteFactorGraph.cpp
14  * @date Feb 14, 2011
15  * @author Duy-Nguyen Ta
16  */
17 
23 
25 
26 #include <boost/assign/std/map.hpp>
27 using namespace boost::assign;
28 
29 using namespace std;
30 using namespace gtsam;
31 
32 /* ************************************************************************* */
33 TEST_UNSAFE( DiscreteFactorGraph, debugScheduler) {
34  DiscreteKey PC(0,4), ME(1, 4), AI(2, 4), A(3, 3);
35 
37  graph.add(AI, "1 0 0 1");
38  graph.add(AI, "1 1 1 0");
39  graph.add(A & AI, "1 1 1 0 1 1 1 1 0 1 1 1");
40  graph.add(ME, "0 1 0 0");
41  graph.add(ME, "1 1 1 0");
42  graph.add(A & ME, "1 1 1 0 1 1 1 1 0 1 1 1");
43  graph.add(PC, "1 0 1 0");
44  graph.add(PC, "1 1 1 0");
45  graph.add(A & PC, "1 1 1 0 1 1 1 1 0 1 1 1");
46  graph.add(ME & AI, "0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
47  graph.add(PC & ME, "0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
48  graph.add(PC & AI, "0 1 1 1 1 0 1 1 1 1 0 1 1 1 1 0");
49 
50 // graph.print("Graph: ");
53 // sum->print("Debug SUM: ");
55 
56 // cond->print("marginal:");
57 
58 // pair<DiscreteBayesNet::shared_ptr, DiscreteFactor::shared_ptr> result = EliminateDiscrete(graph, 1);
59 // result.first->print("BayesNet: ");
60 // result.second->print("New factor: ");
61 //
63  ordering += Key(0),Key(1),Key(2),Key(3);
64  DiscreteEliminationTree eliminationTree(graph, ordering);
65 // eliminationTree.print("Elimination tree: ");
66  eliminationTree.eliminate(EliminateDiscrete);
67 // solver.optimize();
68 // DiscreteBayesNet::shared_ptr bayesNet = solver.eliminate();
69 }
70 
71 /* ************************************************************************* */
73 TEST_UNSAFE( DiscreteFactorGraph, DiscreteFactorGraphEvaluationTest) {
74 
75  // Three keys P1 and P2
76  DiscreteKey P1(0,2), P2(1,2), P3(2,3);
77 
78  // Create the DiscreteFactorGraph
80  graph.add(P1, "0.9 0.3");
81  graph.add(P2, "0.9 0.6");
82  graph.add(P1 & P2, "4 1 10 4");
83 
84  // Instantiate Values
86  values[0] = 1;
87  values[1] = 1;
88 
89  // Check if graph evaluation works ( 0.3*0.6*4 )
90  EXPECT_DOUBLES_EQUAL( .72, graph(values), 1e-9);
91 
92  // Creating a new test with third node and adding unary and ternary factors on it
93  graph.add(P3, "0.9 0.2 0.5");
94  graph.add(P1 & P2 & P3, "1 2 3 4 5 6 7 8 9 10 11 12");
95 
96  // Below values lead to selecting the 8th index in the ternary factor table
97  values[0] = 1;
98  values[1] = 0;
99  values[2] = 1;
100 
101  // Check if graph evaluation works (0.3*0.9*1*0.2*8)
102  EXPECT_DOUBLES_EQUAL( 4.32, graph(values), 1e-9);
103 
104  // Below values lead to selecting the 3rd index in the ternary factor table
105  values[0] = 0;
106  values[1] = 1;
107  values[2] = 0;
108 
109  // Check if graph evaluation works (0.9*0.6*1*0.9*4)
110  EXPECT_DOUBLES_EQUAL( 1.944, graph(values), 1e-9);
111 
112  // Check if graph product works
114  EXPECT_DOUBLES_EQUAL( 1.944, product(values), 1e-9);
115 }
116 
117 /* ************************************************************************* */
119 {
120  // Declare keys and ordering
121  DiscreteKey C(0,2), B(1,2), A(2,2);
122 
123  // A simple factor graph (A)-fAC-(C)-fBC-(B)
124  // with smoothness priors
126  graph.add(A & C, "3 1 1 3");
127  graph.add(C & B, "3 1 1 3");
128 
129  // Test EliminateDiscrete
130  // FIXME: apparently Eliminate returns a conditional rather than a net
131  Ordering frontalKeys;
132  frontalKeys += Key(0);
135  boost::tie(conditional, newFactor) = EliminateDiscrete(graph, frontalKeys);
136 
137  // Check Bayes net
138  CHECK(conditional);
140  Signature signature((C | B, A) = "9/1 1/1 1/1 1/9");
141  // cout << signature << endl;
142  DiscreteConditional expectedConditional(signature);
143  EXPECT(assert_equal(expectedConditional, *conditional));
144  expected.add(signature);
145 
146  // Check Factor
147  CHECK(newFactor);
148  DecisionTreeFactor expectedFactor(B & A, "10 6 6 10");
149  EXPECT(assert_equal(expectedFactor, *newFactor));
150 
151  // add conditionals to complete expected Bayes net
152  expected.add(B | A = "5/3 3/5");
153  expected.add(A % "1/1");
154  // GTSAM_PRINT(expected);
155 
156  // Test elimination tree
158  ordering += Key(0), Key(1), Key(2);
159  DiscreteEliminationTree etree(graph, ordering);
161  DiscreteFactorGraph::shared_ptr remainingGraph;
162  boost::tie(actual, remainingGraph) = etree.eliminate(&EliminateDiscrete);
163  EXPECT(assert_equal(expected, *actual));
164 
165 // // Test solver
166 // DiscreteBayesNet::shared_ptr actual2 = solver.eliminate();
167 // EXPECT(assert_equal(expected, *actual2));
168 
169  // Test optimization
170  DiscreteFactor::Values expectedValues;
171  insert(expectedValues)(0, 0)(1, 0)(2, 0);
172  DiscreteFactor::sharedValues actualValues = graph.optimize();
173  EXPECT(assert_equal(expectedValues, *actualValues));
174 }
175 
176 /* ************************************************************************* */
178 {
179  // Declare a bunch of keys
180  DiscreteKey C(0,2), A(1,2), B(2,2);
181 
182  // Create Factor graph
184  graph.add(C & A, "0.2 0.8 0.3 0.7");
185  graph.add(C & B, "0.1 0.9 0.4 0.6");
186  // graph.product().print();
187  // DiscreteSequentialSolver(graph).eliminate()->print();
188 
189  DiscreteFactor::sharedValues actualMPE = graph.optimize();
190 
191  DiscreteFactor::Values expectedMPE;
192  insert(expectedMPE)(0, 0)(1, 1)(2, 1);
193  EXPECT(assert_equal(expectedMPE, *actualMPE));
194 }
195 
196 /* ************************************************************************* */
197 TEST( DiscreteFactorGraph, testMPE_Darwiche09book_p244)
198 {
199  // The factor graph in Darwiche09book, page 244
200  DiscreteKey A(4,2), C(3,2), S(2,2), T1(0,2), T2(1,2);
201 
202  // Create Factor graph
204  graph.add(S, "0.55 0.45");
205  graph.add(S & C, "0.05 0.95 0.01 0.99");
206  graph.add(C & T1, "0.80 0.20 0.20 0.80");
207  graph.add(S & C & T2, "0.80 0.20 0.20 0.80 0.95 0.05 0.05 0.95");
208  graph.add(T1 & T2 & A, "1 0 0 1 0 1 1 0");
209  graph.add(A, "1 0");// evidence, A = yes (first choice in Darwiche)
210  //graph.product().print("Darwiche-product");
211  // graph.product().potentials().dot("Darwiche-product");
212  // DiscreteSequentialSolver(graph).eliminate()->print();
213 
214  DiscreteFactor::Values expectedMPE;
215  insert(expectedMPE)(4, 0)(2, 0)(3, 1)(0, 1)(1, 1);
216 
217  // Use the solver machinery.
219  DiscreteFactor::sharedValues actualMPE = chordal->optimize();
220  EXPECT(assert_equal(expectedMPE, *actualMPE));
221 // DiscreteConditional::shared_ptr root = chordal->back();
222 // EXPECT_DOUBLES_EQUAL(0.4, (*root)(*actualMPE), 1e-9);
223 
224  // Let us create the Bayes tree here, just for fun, because we don't use it now
225 // typedef JunctionTreeOrdered<DiscreteFactorGraph> JT;
226 // GenericMultifrontalSolver<DiscreteFactor, JT> solver(graph);
227 // BayesTreeOrdered<DiscreteConditional>::shared_ptr bayesTree = solver.eliminate(&EliminateDiscrete);
229 // EXPECT_LONGS_EQUAL(2,bayesTree->size());
230 
232  ordering += Key(0),Key(1),Key(2),Key(3),Key(4);
233  DiscreteBayesTree::shared_ptr bayesTree = graph.eliminateMultifrontal(ordering);
234  // bayesTree->print("Bayes Tree");
235  EXPECT_LONGS_EQUAL(2,bayesTree->size());
236 
237 #ifdef OLD
238 // Create the elimination tree manually
239 VariableIndexOrdered structure(graph);
240 typedef EliminationTreeOrdered<DiscreteFactor> ETree;
241 ETree::shared_ptr eTree = ETree::Create(graph, structure);
242 //eTree->print(">>>>>>>>>>> Elimination Tree <<<<<<<<<<<<<<<<<");
243 
244 // eliminate normally and check solution
245 DiscreteBayesNet::shared_ptr bayesNet = eTree->eliminate(&EliminateDiscrete);
246 // bayesNet->print(">>>>>>>>>>>>>> Bayes Net <<<<<<<<<<<<<<<<<<");
247 DiscreteFactor::sharedValues actualMPE = optimize(*bayesNet);
248 EXPECT(assert_equal(expectedMPE, *actualMPE));
249 
250 // Approximate and check solution
251 // DiscreteBayesNet::shared_ptr approximateNet = eTree->approximate();
252 // approximateNet->print(">>>>>>>>>>>>>> Approximate Net <<<<<<<<<<<<<<<<<<");
253 // EXPECT(assert_equal(expectedMPE, *actualMPE));
254 #endif
255 }
256 #ifdef OLD
257 
258 /* ************************************************************************* */
263 class Key2 {
264 private:
265 std::string wff_;
266 size_t cardinality_;
267 public:
269 Key2(const std::string& name, size_t cardinality = 2) :
270 wff_(name), cardinality_(cardinality) {
271 }
272 const std::string& name() const {
273  return wff_;
274 }
275 
277 friend std::ostream& operator <<(std::ostream &os, const Key2 &key);
278 };
279 
280 struct Factor2 {
281 std::string wff_;
282 Factor2() :
283 wff_("@") {
284 }
285 Factor2(const std::string& s) :
286 wff_(s) {
287 }
288 Factor2(const Key2& key) :
289 wff_(key.name()) {
290 }
291 
292 friend std::ostream& operator <<(std::ostream &os, const Factor2 &f);
293 friend Factor2 operator -(const Key2& key);
294 };
295 
296 std::ostream& operator <<(std::ostream &os, const Factor2 &f) {
297 os << f.wff_;
298 return os;
299 }
300 
302 Factor2 operator -(const Key2& key) {
303 return Factor2("-" + key.name());
304 }
305 
307 Factor2 operator ||(const Factor2 &factor1, const Factor2 &factor2) {
308 return Factor2(std::string("(") + factor1.wff_ + " || " + factor2.wff_ + ")");
309 }
310 
312 Factor2 operator &&(const Factor2 &factor1, const Factor2 &factor2) {
313 return Factor2(std::string("(") + factor1.wff_ + " && " + factor2.wff_ + ")");
314 }
315 
317 Factor2 operator >>(const Factor2 &factor1, const Factor2 &factor2) {
318 return Factor2(std::string("(") + factor1.wff_ + " >> " + factor2.wff_ + ")");
319 }
320 
321 struct Graph2: public std::list<Factor2> {
322 
324 // void operator +=(const Graph2& graph) {
325 // for(const Factor2& f: graph)
326 // push_back(f);
327 // }
328 friend std::ostream& operator <<(std::ostream &os, const Graph2& graph);
329 
330 };
331 
333 //Graph2 operator +=(Graph2& graph, const Factor2& factor) {
334 // graph.push_back(factor);
335 // return graph;
336 //}
337 std::ostream& operator <<(std::ostream &os, const Graph2& graph) {
338 for(const Factor2& f: graph)
339 os << f << endl;
340 return os;
341 }
342 
343 /* ************************************************************************* */
345 {
346 Key2 M("Mythical"), I("Immortal"), A("Mammal"), H("Horned"), G("Magical");
347 
348 // Test this desired construction
349 Graph2 unicorns;
350 unicorns += M >> -A;
351 unicorns += (-M) >> (-I && A);
352 unicorns += (I || A) >> H;
353 unicorns += H >> G;
354 
355 // should be done by adapting boost::assign:
356 // unicorns += (-M) >> (-I && A), (I || A) >> H , H >> G;
357 
358 cout << unicorns;
359 }
360 #endif
361 
362 /* ************************************************************************* */
363 int main() {
364 TestResult tr;
365 return TestRegistry::runAllTests(tr);
366 }
367 /* ************************************************************************* */
368 
#define CHECK(condition)
Definition: Test.h:109
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
A insert(1, 2)=0
void add(const DiscreteKey &j, SOURCE table)
static int runAllTests(TestResult &result)
JacobiRotation< float > G
static enum @843 ordering
Matrix expected
Definition: testMatrix.cpp:974
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
const mpreal operator>>(const mpreal &v, const unsigned long int k)
Definition: mpreal.h:1589
Definition: test.py:1
DiscreteFactor::sharedValues optimize() const
leaf::MyValues values
void add(const Signature &s)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Definition: Half.h:150
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
NonlinearFactorGraph graph
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
Bayes network.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static const Matrix93 P3
Definition: SO3.cpp:317
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
EIGEN_DEVICE_FUNC const CwiseBinaryOp< internal::scalar_boolean_and_op, const Derived, const OtherDerived > operator&&(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
EIGEN_DEVICE_FUNC const CwiseBinaryOp< internal::scalar_boolean_or_op, const Derived, const OtherDerived > operator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
std::ostream & operator<<(std::ostream &s, const Jet< T, N > &z)
Definition: jet.h:631
Key S(std::uint64_t j)
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:34
#define EXPECT(condition)
Definition: Test.h:151
TEST(DiscreteFactorGraph, test)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > eliminate(Eliminate function) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
const mpreal sum(const mpreal tab[], const unsigned long int n, int &status, mp_rnd_t mode=mpreal::get_default_rnd())
Definition: mpreal.h:2381
Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree.
shared_ptr sum(size_t nrFrontals) const
Create new factor by summing all values with the same separator values.
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
static const Matrix I
Definition: lago.cpp:35
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
static const Point3 P2(3.5,-8.2, 4.2)
traits
Definition: chartTesting.h:28
boost::shared_ptr< This > shared_ptr
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
ofstream os("timeSchurFactors.csv")
TEST_UNSAFE(DiscreteFactorGraph, debugScheduler)
boost::shared_ptr< Values > sharedValues
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63
boost::shared_ptr< DecisionTreeFactor > shared_ptr
boost::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
boost::shared_ptr< This > shared_ptr
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
Jet< T, N > operator-(const Jet< T, N > &f)
Definition: jet.h:258
Annotation for function names.
Definition: attr.h:36
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
DecisionTreeFactor product() const
void product(const MatrixType &m)
Definition: product.h:20
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


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