| 1 | /* |
| 2 | * testFindSeparator.cpp |
| 3 | * |
| 4 | * Created on: Nov 23, 2010 |
| 5 | * Author: nikai |
| 6 | * Description: unit tests for FindSeparator |
| 7 | */ |
| 8 | |
| 9 | #include <CppUnitLite/TestHarness.h> |
| 10 | |
| 11 | #include <gtsam_unstable/partition/FindSeparator-inl.h> |
| 12 | #include <gtsam_unstable/partition/GenericGraph.h> |
| 13 | |
| 14 | using namespace std; |
| 15 | using namespace gtsam; |
| 16 | using namespace gtsam::partition; |
| 17 | |
| 18 | /* ************************************************************************* */ |
| 19 | // x0 - x1 - x2 |
| 20 | // l3 l4 |
| 21 | TEST ( Partition, separatorPartitionByMetis ) |
| 22 | { |
| 23 | GenericGraph2D graph; |
| 24 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 0, args: NODE_POSE_2D, args: 3, args: NODE_LANDMARK_2D)); |
| 25 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 2, args: NODE_POSE_2D, args: 4, args: NODE_LANDMARK_2D)); |
| 26 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 0, args: NODE_POSE_2D, args: 1, args: NODE_POSE_2D)); |
| 27 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 2, args: NODE_POSE_2D)); |
| 28 | std::vector<size_t> keys{0, 1, 2, 3, 4}; |
| 29 | |
| 30 | WorkSpace workspace(5); |
| 31 | std::optional<MetisResult> actual = separatorPartitionByMetis<GenericGraph2D>(graph, keys, |
| 32 | workspace, verbose: true); |
| 33 | |
| 34 | CHECK(actual.has_value()); |
| 35 | vector<size_t> A_expected{0, 3}; // frontal |
| 36 | vector<size_t> B_expected{2, 4}; // frontal |
| 37 | vector<size_t> C_expected{1}; // separator |
| 38 | CHECK(A_expected == actual->A); |
| 39 | CHECK(B_expected == actual->B); |
| 40 | CHECK(C_expected == actual->C); |
| 41 | } |
| 42 | |
| 43 | /* ************************************************************************* */ |
| 44 | // x1 - x2 - x3, variable not used x0, x4, l7 |
| 45 | // l5 l6 |
| 46 | TEST ( Partition, separatorPartitionByMetis2 ) |
| 47 | { |
| 48 | GenericGraph2D graph; |
| 49 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 5, args: NODE_LANDMARK_2D)); |
| 50 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 3, args: NODE_POSE_2D, args: 6, args: NODE_LANDMARK_2D)); |
| 51 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 2, args: NODE_POSE_2D)); |
| 52 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 2, args: NODE_POSE_2D, args: 3, args: NODE_POSE_2D)); |
| 53 | std::vector<size_t> keys{1, 2, 3, 5, 6}; |
| 54 | |
| 55 | WorkSpace workspace(8); |
| 56 | std::optional<MetisResult> actual = separatorPartitionByMetis<GenericGraph2D>(graph, keys, |
| 57 | workspace, verbose: true); |
| 58 | |
| 59 | CHECK(actual.has_value()); |
| 60 | vector<size_t> A_expected{1, 5}; // frontal |
| 61 | vector<size_t> B_expected{3, 6}; // frontal |
| 62 | vector<size_t> C_expected{2}; // separator |
| 63 | CHECK(A_expected == actual->A); |
| 64 | CHECK(B_expected == actual->B); |
| 65 | CHECK(C_expected == actual->C); |
| 66 | } |
| 67 | |
| 68 | /* *************************************************************************/ |
| 69 | // x0 - x1 - x2 - x3 |
| 70 | TEST ( Partition, edgePartitionByMetis ) |
| 71 | { |
| 72 | GenericGraph3D graph; |
| 73 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 0, args: 1, args: 0, args: NODE_POSE_3D, args: NODE_POSE_3D)); |
| 74 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 1, args: 2, args: 1, args: NODE_POSE_3D, args: NODE_POSE_3D)); |
| 75 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 2, args: 3, args: 2, args: NODE_POSE_3D, args: NODE_POSE_3D)); |
| 76 | std::vector<size_t> keys{0, 1, 2, 3}; |
| 77 | |
| 78 | WorkSpace workspace(6); |
| 79 | std::optional<MetisResult> actual = edgePartitionByMetis<GenericGraph3D>(graph, keys, |
| 80 | workspace, verbose: true); |
| 81 | |
| 82 | CHECK(actual.has_value()); |
| 83 | vector<size_t> A_expected{0, 1}; // frontal |
| 84 | vector<size_t> B_expected{2, 3}; // frontal |
| 85 | vector<size_t> C_expected; // separator |
| 86 | // for(const size_t a: actual->A) |
| 87 | // cout << a << " "; |
| 88 | // cout << endl; |
| 89 | // for(const size_t b: actual->B) |
| 90 | // cout << b << " "; |
| 91 | // cout << endl; |
| 92 | |
| 93 | CHECK(A_expected == actual->A || A_expected == actual->B); |
| 94 | CHECK(B_expected == actual->B || B_expected == actual->A); |
| 95 | CHECK(C_expected == actual->C); |
| 96 | } |
| 97 | |
| 98 | /* *************************************************************************/ |
| 99 | // x0 - x1 - x2 - x3 - x4 |
| 100 | TEST ( Partition, edgePartitionByMetis2 ) |
| 101 | { |
| 102 | GenericGraph3D graph; |
| 103 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 0, args: 1, args: 0, args: NODE_POSE_3D, args: NODE_POSE_3D, args: 1)); |
| 104 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 1, args: 2, args: 1, args: NODE_POSE_3D, args: NODE_POSE_3D, args: 1)); |
| 105 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 2, args: 3, args: 2, args: NODE_POSE_3D, args: NODE_POSE_3D, args: 20)); |
| 106 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 3, args: 4, args: 3, args: NODE_POSE_3D, args: NODE_POSE_3D, args: 1)); |
| 107 | //QNX Testing: fix tiebreaker to match |
| 108 | #if !defined(__QNX__) |
| 109 | std::vector<size_t> keys{0, 1, 2, 3, 4}; |
| 110 | #else |
| 111 | //Anything where 2 is before 0 will work. |
| 112 | std::vector<size_t> keys{2, 0, 3, 1, 4}; |
| 113 | #endif |
| 114 | |
| 115 | WorkSpace workspace(6); |
| 116 | std::optional<MetisResult> actual = edgePartitionByMetis<GenericGraph3D>(graph, keys, |
| 117 | workspace, verbose: true); |
| 118 | CHECK(actual.has_value()); |
| 119 | vector<size_t> A_expected{0, 1}; // frontal |
| 120 | vector<size_t> B_expected{2, 3, 4}; // frontal |
| 121 | vector<size_t> C_expected; // separator |
| 122 | CHECK(A_expected == actual->A); |
| 123 | CHECK(B_expected == actual->B); |
| 124 | CHECK(C_expected == actual->C); |
| 125 | } |
| 126 | |
| 127 | /* ************************************************************************* */ |
| 128 | // x0 - x1 - x2 |
| 129 | // l3 l4 |
| 130 | TEST ( Partition, findSeparator ) |
| 131 | { |
| 132 | GenericGraph2D graph; |
| 133 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 0, args: NODE_POSE_2D, args: 3, args: NODE_LANDMARK_2D)); |
| 134 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 2, args: NODE_POSE_2D, args: 4, args: NODE_LANDMARK_2D)); |
| 135 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 0, args: NODE_POSE_2D, args: 1, args: NODE_POSE_2D)); |
| 136 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 2, args: NODE_POSE_2D)); |
| 137 | std::vector<size_t> keys{0, 1, 2, 3, 4}; |
| 138 | |
| 139 | WorkSpace workspace(5); |
| 140 | int minNodesPerMap = -1; |
| 141 | bool reduceGraph = false; |
| 142 | int numSubmaps = findSeparator<GenericGraph2D>(graph, keys, minNodesPerMap, workspace, |
| 143 | verbose: false, int2symbol: {}, reduceGraph, minNrConstraintsPerCamera: 0, minNrConstraintsPerLandmark: 0); |
| 144 | LONGS_EQUAL(2, numSubmaps); |
| 145 | LONGS_EQUAL(5, workspace.partitionTable.size()); |
| 146 | LONGS_EQUAL(1, workspace.partitionTable[0]); |
| 147 | LONGS_EQUAL(0, workspace.partitionTable[1]); |
| 148 | LONGS_EQUAL(2, workspace.partitionTable[2]); |
| 149 | LONGS_EQUAL(1, workspace.partitionTable[3]); |
| 150 | LONGS_EQUAL(2, workspace.partitionTable[4]); |
| 151 | } |
| 152 | |
| 153 | /* ************************************************************************* */ |
| 154 | // x1 - x2 - x3, variable not used x0, x4, l7 |
| 155 | // l5 l6 |
| 156 | TEST ( Partition, findSeparator2 ) |
| 157 | { |
| 158 | GenericGraph2D graph; |
| 159 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 5, args: NODE_LANDMARK_2D)); |
| 160 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 3, args: NODE_POSE_2D, args: 6, args: NODE_LANDMARK_2D)); |
| 161 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 1, args: NODE_POSE_2D, args: 2, args: NODE_POSE_2D)); |
| 162 | graph.push_back(x: std::make_shared<GenericFactor2D>(args: 2, args: NODE_POSE_2D, args: 3, args: NODE_POSE_2D)); |
| 163 | std::vector<size_t> keys{1, 2, 3, 5, 6}; |
| 164 | |
| 165 | WorkSpace workspace(8); |
| 166 | int minNodesPerMap = -1; |
| 167 | bool reduceGraph = false; |
| 168 | int numSubmaps = findSeparator<GenericGraph2D>(graph, keys, minNodesPerMap, workspace, |
| 169 | verbose: false, int2symbol: {}, reduceGraph, minNrConstraintsPerCamera: 0, minNrConstraintsPerLandmark: 0); |
| 170 | LONGS_EQUAL(2, numSubmaps); |
| 171 | LONGS_EQUAL(8, workspace.partitionTable.size()); |
| 172 | LONGS_EQUAL(-1,workspace.partitionTable[0]); |
| 173 | LONGS_EQUAL(1, workspace.partitionTable[1]); |
| 174 | LONGS_EQUAL(0, workspace.partitionTable[2]); |
| 175 | LONGS_EQUAL(2, workspace.partitionTable[3]); |
| 176 | LONGS_EQUAL(-1,workspace.partitionTable[4]); |
| 177 | LONGS_EQUAL(1, workspace.partitionTable[5]); |
| 178 | LONGS_EQUAL(2, workspace.partitionTable[6]); |
| 179 | LONGS_EQUAL(-1,workspace.partitionTable[7]); |
| 180 | } |
| 181 | |
| 182 | /* *************************************************************************/ |
| 183 | /** |
| 184 | * l1-l8 l9-l16 l17-l24 |
| 185 | * / | / \ | \ |
| 186 | * x25 x26 x27 x28 |
| 187 | */ |
| 188 | TEST ( Partition, findSeparator3_with_reduced_camera ) |
| 189 | { |
| 190 | GenericGraph3D graph; |
| 191 | for (int j=1; j<=8; j++) |
| 192 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 25, args&: j)); |
| 193 | for (int j=1; j<=16; j++) |
| 194 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 26, args&: j)); |
| 195 | for (int j=9; j<=24; j++) |
| 196 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 27, args&: j)); |
| 197 | for (int j=17; j<=24; j++) |
| 198 | graph.push_back(x: std::make_shared<GenericFactor3D>(args: 28, args&: j)); |
| 199 | |
| 200 | std::vector<size_t> keys; |
| 201 | for(int i=1; i<=28; i++) |
| 202 | keys.push_back(x: i); |
| 203 | |
| 204 | vector<Symbol> int2symbol; |
| 205 | int2symbol.push_back(x: Symbol('x',0)); // dummy |
| 206 | for(int i=1; i<=24; i++) |
| 207 | int2symbol.push_back(x: Symbol('l',i)); |
| 208 | int2symbol.push_back(x: Symbol('x',25)); |
| 209 | int2symbol.push_back(x: Symbol('x',26)); |
| 210 | int2symbol.push_back(x: Symbol('x',27)); |
| 211 | int2symbol.push_back(x: Symbol('x',28)); |
| 212 | |
| 213 | WorkSpace workspace(29); |
| 214 | bool reduceGraph = true; |
| 215 | int numIsland = findSeparator(graph, keys, minNodesPerMap: 3, workspace, verbose: false, int2symbol, reduceGraph, minNrConstraintsPerCamera: 0, minNrConstraintsPerLandmark: 0); |
| 216 | LONGS_EQUAL(2, numIsland); |
| 217 | |
| 218 | partition::PartitionTable& partitionTable = workspace.partitionTable; |
| 219 | for (int j=1; j<=8; j++) |
| 220 | LONGS_EQUAL(1, partitionTable[j]); |
| 221 | for (int j=9; j<=16; j++) |
| 222 | LONGS_EQUAL(0, partitionTable[j]); |
| 223 | for (int j=17; j<=24; j++) |
| 224 | LONGS_EQUAL(2, partitionTable[j]); |
| 225 | LONGS_EQUAL(1, partitionTable[25]); |
| 226 | LONGS_EQUAL(1, partitionTable[26]); |
| 227 | LONGS_EQUAL(2, partitionTable[27]); |
| 228 | LONGS_EQUAL(2, partitionTable[28]); |
| 229 | } |
| 230 | |
| 231 | /* ************************************************************************* */ |
| 232 | int main() { TestResult tr; return TestRegistry::runAllTests(result&: tr);} |
| 233 | /* ************************************************************************* */ |
| 234 | |