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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:53