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, AppendKey) {
201  using symbol_shorthand::X;
202  Ordering actual;
203  actual += X(0);
204 
205  Ordering expected1{X(0)};
206  EXPECT(assert_equal(expected1, actual));
207 
208  actual += X(1), X(2), X(3);
209  Ordering expected2{X(0), X(1), X(2), X(3)};
210  EXPECT(assert_equal(expected2, actual));
211 }
212 
213 /* ************************************************************************* */
214 TEST(Ordering, AppendVector) {
215  using symbol_shorthand::X;
216  KeyVector keys{X(0), X(1), X(2)};
217  Ordering actual;
218  actual += keys;
219 
220  Ordering expected{X(0), X(1), X(2)};
221  EXPECT(assert_equal(expected, actual));
222 
223  actual = Ordering();
224  Ordering addl{X(0), X(1), X(2)};
225  actual += addl;
226  EXPECT(assert_equal(expected, actual));
227 }
228 
229 /* ************************************************************************* */
230 TEST(Ordering, Contains) {
231  using symbol_shorthand::X;
232  Ordering ordering{X(0), X(1), X(2)};
233 
234  EXPECT(ordering.contains(X(1)));
235  EXPECT(!ordering.contains(X(4)));
236 }
237 
238 /* ************************************************************************* */
239 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
240 TEST(Ordering, csr_format_4) {
241  SymbolicFactorGraph symbolicGraph;
242 
243  symbolicGraph.push_factor(Symbol('x', 1));
244  symbolicGraph.push_factor(Symbol('x', 1), Symbol('x', 2));
245  symbolicGraph.push_factor(Symbol('x', 2), Symbol('x', 3));
246  symbolicGraph.push_factor(Symbol('x', 3), Symbol('x', 4));
247  symbolicGraph.push_factor(Symbol('x', 4), Symbol('x', 5));
248  symbolicGraph.push_factor(Symbol('x', 5), Symbol('x', 6));
249 
250  MetisIndex mi(symbolicGraph);
251 
252  const vector<int> xadjExpected{0, 1, 3, 5, 7, 9, 10},
253  adjExpected{1, 0, 2, 1, 3, 2, 4, 3, 5, 4};
254 
255  vector<int> adjAcutal = mi.adj();
256  vector<int> xadjActual = mi.xadj();
257 
258  EXPECT(xadjExpected == mi.xadj());
259  EXPECT(adjExpected.size() == mi.adj().size());
260  EXPECT(adjExpected == adjAcutal);
261 
262  Ordering metOrder = Ordering::Metis(symbolicGraph);
263 
264  // Test different symbol types
265  symbolicGraph.push_factor(Symbol('l', 1));
266  symbolicGraph.push_factor(Symbol('x', 1), Symbol('l', 1));
267  symbolicGraph.push_factor(Symbol('x', 2), Symbol('l', 1));
268  symbolicGraph.push_factor(Symbol('x', 3), Symbol('l', 1));
269  symbolicGraph.push_factor(Symbol('x', 4), Symbol('l', 1));
270 
271  Ordering metOrder2 = Ordering::Metis(symbolicGraph);
272 }
273 #endif
274 /* ************************************************************************* */
275 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
276 TEST(Ordering, metis) {
277 
278  SymbolicFactorGraph symbolicGraph;
279 
280  symbolicGraph.push_factor(0);
281  symbolicGraph.push_factor(0, 1);
282  symbolicGraph.push_factor(1, 2);
283 
284  MetisIndex mi(symbolicGraph);
285 
286  const vector<int> xadjExpected{0, 1, 3, 4}, adjExpected{1, 0, 2, 1};
287 
288  EXPECT(xadjExpected == mi.xadj());
289  EXPECT(adjExpected.size() == mi.adj().size());
290  EXPECT(adjExpected == mi.adj());
291 
292  Ordering metis = Ordering::Metis(symbolicGraph);
293 }
294 #endif
295 /* ************************************************************************* */
296 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
297 TEST(Ordering, MetisLoop) {
298 
299  // create linear graph
301 
302  // add loop closure
303  symbolicGraph.push_factor(0, 5);
304 
305  // METIS
306 #if defined(__APPLE__)
307  {
308  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
309  // - P( 1 0 3)
310  // | - P( 4 | 0 3)
311  // | | - P( 5 | 0 4)
312  // | - P( 2 | 1 3)
313  Ordering expected = Ordering({5, 4, 2, 1, 0, 3});
314  EXPECT(assert_equal(expected, actual));
315  }
316 #elif defined(_WIN32)
317  {
318  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
319  // - P( 0 5 2)
320  // | - P( 3 | 5 2)
321  // | | - P( 4 | 5 3)
322  // | - P( 1 | 0 2)
323  Ordering expected = Ordering({4, 3, 1, 0, 5, 2});
324  EXPECT(assert_equal(expected, actual));
325  }
326 #else
327  {
328  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
329  // - P( 0 4 1)
330  // | - P( 2 | 4 1)
331  // | | - P( 3 | 4 2)
332  // | - P( 5 | 0 1)
333  Ordering expected = Ordering({3, 2, 5, 0, 4, 1});
334  EXPECT(assert_equal(expected, actual));
335  }
336 #endif
337 }
338 #endif
339 /* ************************************************************************* */
340 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
341 TEST(Ordering, MetisEmptyGraph) {
342  SymbolicFactorGraph symbolicGraph;
343 
344  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
346  EXPECT(assert_equal(expected, actual));
347 }
348 #endif
349 /* ************************************************************************* */
350 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
351 TEST(Ordering, MetisSingleNode) {
352  // create graph with a single node
353  SymbolicFactorGraph symbolicGraph;
354  symbolicGraph.push_factor(7);
355 
356  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
357  Ordering expected = Ordering({7});
358  EXPECT(assert_equal(expected, actual));
359 }
360 #endif
361 /* ************************************************************************* */
362 TEST(Ordering, Create) {
363 
364  // create chain graph
366 
367  // COLAMD
368  {
369  //- P( 4 5)
370  //| - P( 3 | 4)
371  //| | - P( 2 | 3)
372  //| | | - P( 1 | 2)
373  //| | | | - P( 0 | 1)
374  Ordering actual = Ordering::Create(Ordering::COLAMD, symbolicGraph);
375  Ordering expected = Ordering({0, 1, 2, 3, 4, 5});
376  EXPECT(assert_equal(expected, actual));
377  }
378 
379 #ifdef GTSAM_SUPPORT_NESTED_DISSECTION
380  // METIS
381  {
382  Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph);
383  //- P( 1 0 2)
384  //| - P( 3 4 | 2)
385  //| | - P( 5 | 4)
386  Ordering expected = Ordering({5, 3, 4, 1, 0, 2});
387  EXPECT(assert_equal(expected, actual));
388  }
389 #endif
390 
391  // CUSTOM
392  CHECK_EXCEPTION(Ordering::Create(Ordering::CUSTOM, symbolicGraph), runtime_error);
393 }
394 
395 /* ************************************************************************* */
396 int main() {
397  TestResult tr;
398  return TestRegistry::runAllTests(tr);
399 }
400 /* ************************************************************************* */
gtsam::SymbolicFactorGraph::push_factor
void push_factor(Key key)
Definition: SymbolicFactorGraph.cpp:42
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
CHECK_EXCEPTION
#define CHECK_EXCEPTION(condition, exception_name)
Definition: Test.h:118
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::FastMap
Definition: FastMap.h:39
gtsam::MetisIndex::adj
const std::vector< int32_t > & adj() const
Definition: MetisIndex.h:88
Ordering.h
Variable ordering for the elimination algorithm.
X
#define X
Definition: icosphere.cpp:20
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
TestableAssertions.h
Provides additional testing facilities for common data structures.
example
Definition: testOrdering.cpp:28
gtsam::MetisIndex::xadj
const std::vector< int32_t > & xadj() const
Definition: MetisIndex.h:85
gtsam::SymbolicFactorGraph
Definition: SymbolicFactorGraph.h:61
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::MetisIndex
Definition: MetisIndex.h:37
example::symbolicChain
SymbolicFactorGraph symbolicChain()
Definition: testOrdering.cpp:29
main
int main()
Definition: testOrdering.cpp:396
Symbol.h
SymbolicFactorGraph.h
ordering
static enum @1096 ordering
TestResult
Definition: TestResult.h:26
TEST
TEST(Ordering, constrained_ordering)
Definition: testOrdering.cpp:40
empty
Definition: test_copy_move.cpp:19
gtsam
traits
Definition: chartTesting.h:28
std
Definition: BFloat16.h:88
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
MetisIndex.h
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::Symbol
Definition: inference/Symbol.h:37


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:09:51