testOrdering.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 <gtsam/inference/Symbol.h>
24 
25 #include <boost/assign/std.hpp>
26 
27 using namespace std;
28 using namespace gtsam;
29 using namespace boost::assign;
30 
31 namespace example {
33  SymbolicFactorGraph symbolicGraph;
34  symbolicGraph.push_factor(0, 1);
35  symbolicGraph.push_factor(1, 2);
36  symbolicGraph.push_factor(2, 3);
37  symbolicGraph.push_factor(3, 4);
38  symbolicGraph.push_factor(4, 5);
39  return symbolicGraph;
40 }
41 }
42 /* ************************************************************************* */
43 TEST(Ordering, constrained_ordering) {
44  // create graph with wanted variable set = 2, 4
46 
47  // unconstrained version
48  {
49  Ordering actual = Ordering::Colamd(symbolicGraph);
50  Ordering expected = Ordering(list_of(0)(1)(2)(3)(4)(5));
51  EXPECT(assert_equal(expected, actual));
52  }
53 
54  // constrained version - push one set to the end
55  {
56  Ordering actual = Ordering::ColamdConstrainedLast(symbolicGraph, list_of(2)(4));
57  Ordering expected = Ordering(list_of(0)(1)(5)(3)(4)(2));
58  EXPECT(assert_equal(expected, actual));
59  }
60 
61  // constrained version - push one set to the start
62  {
63  Ordering actual = Ordering::ColamdConstrainedFirst(symbolicGraph, list_of(2)(4));
64  Ordering expected = Ordering(list_of(2)(4)(0)(1)(3)(5));
65  EXPECT(assert_equal(expected, actual));
66  }
67 
68  // Make sure giving empty constraints does not break the code
69  {
70  Ordering actual = Ordering::ColamdConstrainedLast(symbolicGraph, {});
71  Ordering expected = Ordering(list_of(0)(1)(2)(3)(4)(5));
72  EXPECT(assert_equal(expected, actual));
73  }
74  {
75  Ordering actual = Ordering::ColamdConstrainedFirst(symbolicGraph, {});
76  Ordering expected = Ordering(list_of(0)(1)(2)(3)(4)(5));
77  EXPECT(assert_equal(expected, actual));
78  }
79 
80  // Make sure giving empty graph does not break the code
81  SymbolicFactorGraph emptyGraph;
83  {
84  Ordering actual = Ordering::ColamdConstrainedLast(emptyGraph, list_of(2)(4));
85  EXPECT(assert_equal(empty, actual));
86  }
87  {
88  Ordering actual = Ordering::ColamdConstrainedFirst(emptyGraph, list_of(2)(4));
89  EXPECT(assert_equal(empty, actual));
90  }
91 }
92 
93 /* ************************************************************************* */
94 TEST(Ordering, grouped_constrained_ordering) {
95 
96  // create graph with constrained groups:
97  // 1: 2, 4
98  // 2: 5
100 
101  // constrained version - push one set to the end
102  FastMap<Key, int> constraints;
103  constraints[2] = 1;
104  constraints[4] = 1;
105  constraints[5] = 2;
106 
107  Ordering actual = Ordering::ColamdConstrained(symbolicGraph, constraints);
108  Ordering expected = list_of(0)(1)(3)(2)(4)(5);
109  EXPECT(assert_equal(expected, actual));
110 }
111 
112 /* ************************************************************************* */
113 TEST(Ordering, csr_format) {
114  // Example in METIS manual
115  SymbolicFactorGraph symbolicGraph;
116  symbolicGraph.push_factor(0, 1);
117  symbolicGraph.push_factor(1, 2);
118  symbolicGraph.push_factor(2, 3);
119  symbolicGraph.push_factor(3, 4);
120  symbolicGraph.push_factor(5, 6);
121  symbolicGraph.push_factor(6, 7);
122  symbolicGraph.push_factor(7, 8);
123  symbolicGraph.push_factor(8, 9);
124  symbolicGraph.push_factor(10, 11);
125  symbolicGraph.push_factor(11, 12);
126  symbolicGraph.push_factor(12, 13);
127  symbolicGraph.push_factor(13, 14);
128 
129  symbolicGraph.push_factor(0, 5);
130  symbolicGraph.push_factor(5, 10);
131  symbolicGraph.push_factor(1, 6);
132  symbolicGraph.push_factor(6, 11);
133  symbolicGraph.push_factor(2, 7);
134  symbolicGraph.push_factor(7, 12);
135  symbolicGraph.push_factor(3, 8);
136  symbolicGraph.push_factor(8, 13);
137  symbolicGraph.push_factor(4, 9);
138  symbolicGraph.push_factor(9, 14);
139 
140  MetisIndex mi(symbolicGraph);
141 
142  vector<int> xadjExpected, adjExpected;
143  xadjExpected += 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44;
144  adjExpected += 1, 5, 0, 2, 6, 1, 3, 7, 2, 4, 8, 3, 9, 0, 6, 10, 1, 5, 7, 11, 2, 6, 8, 12, 3, 7, 9, 13, 4, 8, 14, 5, 11, 6, 10, 12, 7, 11, 13, 8, 12, 14, 9, 13;
145 
146  EXPECT(xadjExpected == mi.xadj());
147  EXPECT(adjExpected.size() == mi.adj().size());
148  EXPECT(adjExpected == mi.adj());
149 }
150 
151 /* ************************************************************************* */
152 TEST(Ordering, csr_format_2) {
153  SymbolicFactorGraph symbolicGraph;
154 
155  symbolicGraph.push_factor(0);
156  symbolicGraph.push_factor(0, 1);
157  symbolicGraph.push_factor(1, 2);
158  symbolicGraph.push_factor(2, 3);
159  symbolicGraph.push_factor(3, 4);
160  symbolicGraph.push_factor(4, 1);
161 
162  MetisIndex mi(symbolicGraph);
163 
164  vector<int> xadjExpected, adjExpected;
165  xadjExpected += 0, 1, 4, 6, 8, 10;
166  adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3;
167 
168  EXPECT(xadjExpected == mi.xadj());
169  EXPECT(adjExpected.size() == mi.adj().size());
170  EXPECT(adjExpected == mi.adj());
171 }
172 
173 /* ************************************************************************* */
174 TEST(Ordering, csr_format_3) {
175  SymbolicFactorGraph symbolicGraph;
176 
177  symbolicGraph.push_factor(100);
178  symbolicGraph.push_factor(100, 101);
179  symbolicGraph.push_factor(101, 102);
180  symbolicGraph.push_factor(102, 103);
181  symbolicGraph.push_factor(103, 104);
182  symbolicGraph.push_factor(104, 101);
183 
184  MetisIndex mi(symbolicGraph);
185 
186  vector<int> xadjExpected, adjExpected;
187  xadjExpected += 0, 1, 4, 6, 8, 10;
188  adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3;
189  //size_t minKey = mi.minKey();
190 
191  vector<int> adjAcutal = mi.adj();
192 
193  // Normalize, subtract the smallest key
194  //std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(),
195  // std::bind2nd(std::minus<size_t>(), minKey));
196 
197  EXPECT(xadjExpected == mi.xadj());
198  EXPECT(adjExpected.size() == mi.adj().size());
199  EXPECT(adjExpected == adjAcutal);
200 }
201 
202 /* ************************************************************************* */
203 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
204 TEST(Ordering, csr_format_4) {
205  SymbolicFactorGraph symbolicGraph;
206 
207  symbolicGraph.push_factor(Symbol('x', 1));
208  symbolicGraph.push_factor(Symbol('x', 1), Symbol('x', 2));
209  symbolicGraph.push_factor(Symbol('x', 2), Symbol('x', 3));
210  symbolicGraph.push_factor(Symbol('x', 3), Symbol('x', 4));
211  symbolicGraph.push_factor(Symbol('x', 4), Symbol('x', 5));
212  symbolicGraph.push_factor(Symbol('x', 5), Symbol('x', 6));
213 
214  MetisIndex mi(symbolicGraph);
215 
216  vector<int> xadjExpected, adjExpected;
217  xadjExpected += 0, 1, 3, 5, 7, 9, 10;
218  adjExpected += 1, 0, 2, 1, 3, 2, 4, 3, 5, 4;
219 
220  vector<int> adjAcutal = mi.adj();
221  vector<int> xadjActual = mi.xadj();
222 
223  EXPECT(xadjExpected == mi.xadj());
224  EXPECT(adjExpected.size() == mi.adj().size());
225  EXPECT(adjExpected == adjAcutal);
226 
227  Ordering metOrder = Ordering::Metis(symbolicGraph);
228 
229  // Test different symbol types
230  symbolicGraph.push_factor(Symbol('l', 1));
231  symbolicGraph.push_factor(Symbol('x', 1), Symbol('l', 1));
232  symbolicGraph.push_factor(Symbol('x', 2), Symbol('l', 1));
233  symbolicGraph.push_factor(Symbol('x', 3), Symbol('l', 1));
234  symbolicGraph.push_factor(Symbol('x', 4), Symbol('l', 1));
235 
236  Ordering metOrder2 = Ordering::Metis(symbolicGraph);
237 }
238 #endif
239 /* ************************************************************************* */
240 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
241 TEST(Ordering, metis) {
242 
243  SymbolicFactorGraph symbolicGraph;
244 
245  symbolicGraph.push_factor(0);
246  symbolicGraph.push_factor(0, 1);
247  symbolicGraph.push_factor(1, 2);
248 
249  MetisIndex mi(symbolicGraph);
250 
251  vector<int> xadjExpected, adjExpected;
252  xadjExpected += 0, 1, 3, 4;
253  adjExpected += 1, 0, 2, 1;
254 
255  EXPECT(xadjExpected == mi.xadj());
256  EXPECT(adjExpected.size() == mi.adj().size());
257  EXPECT(adjExpected == mi.adj());
258 
259  Ordering metis = Ordering::Metis(symbolicGraph);
260 }
261 #endif
262 /* ************************************************************************* */
263 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
264 TEST(Ordering, MetisLoop) {
265 
266  // create linear graph
268 
269  // add loop closure
270  symbolicGraph.push_factor(0, 5);
271 
272  // METIS
273 #if !defined(__APPLE__)
274  {
275  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
276  // - P( 0 4 1)
277  // | - P( 2 | 4 1)
278  // | | - P( 3 | 4 2)
279  // | - P( 5 | 0 1)
280  Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1));
281  EXPECT(assert_equal(expected, actual));
282  }
283 #else
284  {
285  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
286  // - P( 1 0 3)
287  // | - P( 4 | 0 3)
288  // | | - P( 5 | 0 4)
289  // | - P( 2 | 1 3)
290  Ordering expected = Ordering(list_of(5)(4)(2)(1)(0)(3));
291  EXPECT(assert_equal(expected, actual));
292  }
293 #endif
294 }
295 #endif
296 /* ************************************************************************* */
297 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
298 TEST(Ordering, MetisEmptyGraph) {
299  SymbolicFactorGraph symbolicGraph;
300 
301  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
303  EXPECT(assert_equal(expected, actual));
304 }
305 #endif
306 /* ************************************************************************* */
307 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
308 TEST(Ordering, MetisSingleNode) {
309  // create graph with a single node
310  SymbolicFactorGraph symbolicGraph;
311  symbolicGraph.push_factor(7);
312 
313  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
314  Ordering expected = Ordering(list_of(7));
315  EXPECT(assert_equal(expected, actual));
316 }
317 #endif
318 /* ************************************************************************* */
319 TEST(Ordering, Create) {
320 
321  // create chain graph
323 
324  // COLAMD
325  {
326  //- P( 4 5)
327  //| - P( 3 | 4)
328  //| | - P( 2 | 3)
329  //| | | - P( 1 | 2)
330  //| | | | - P( 0 | 1)
331  Ordering actual = Ordering::Create(Ordering::COLAMD, symbolicGraph);
332  Ordering expected = Ordering(list_of(0)(1)(2)(3)(4)(5));
333  EXPECT(assert_equal(expected, actual));
334  }
335 
336 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
337  // METIS
338  {
339  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
340  //- P( 1 0 2)
341  //| - P( 3 4 | 2)
342  //| | - P( 5 | 4)
343  Ordering expected = Ordering(list_of(5)(3)(4)(1)(0)(2));
344  EXPECT(assert_equal(expected, actual));
345  }
346 #endif
347 
348  // CUSTOM
349  CHECK_EXCEPTION(Ordering::Create(Ordering::CUSTOM, symbolicGraph), runtime_error);
350 }
351 
352 /* ************************************************************************* */
353 int main() {
354  TestResult tr;
355  return TestRegistry::runAllTests(tr);
356 }
357 /* ************************************************************************* */
Provides additional testing facilities for common data structures.
static int runAllTests(TestResult &result)
Matrix expected
Definition: testMatrix.cpp:974
int main()
Definition: Half.h:150
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:119
#define EXPECT(condition)
Definition: Test.h:151
const std::vector< int32_t > & xadj() const
Definition: MetisIndex.h:84
SymbolicFactorGraph symbolicChain()
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
TEST(Ordering, constrained_ordering)
const std::vector< int32_t > & adj() const
Definition: MetisIndex.h:87


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:26