testGraph.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 
23 #include <gtsam/inference/graph.h>
24 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/geometry/Pose2.h>
26 
28 
29 #include <memory>
30 
31 #include <iostream>
32 
33 using namespace std;
34 using namespace gtsam;
35 
36 /* ************************************************************************* */
37 // x1 -> x2
38 // -> x3 -> x4
39 // -> x5
41  PredecessorMap<Key> p_map;
42  p_map.insert(1,1);
43  p_map.insert(2,1);
44  p_map.insert(3,1);
45  p_map.insert(4,3);
46  p_map.insert(5,1);
47 
48  list<Key> expected{4, 5, 3, 2, 1};
49 
50  list<Key> actual = predecessorMap2Keys<Key>(p_map);
51  LONGS_EQUAL((long)expected.size(), (long)actual.size());
52 
53  list<Key>::const_iterator it1 = expected.begin();
54  list<Key>::const_iterator it2 = actual.begin();
55  for(; it1!=expected.end(); it1++, it2++)
56  CHECK(*it1 == *it2)
57 }
58 
59 /* ************************************************************************* */
61 {
62  typedef SGraph<string>::Vertex SVertex;
64  SVertex root;
65  map<Key, SVertex> key2vertex;
66 
67  PredecessorMap<Key> p_map;
68  p_map.insert(1, 2);
69  p_map.insert(2, 2);
70  p_map.insert(3, 2);
71  std::tie(graph, root, key2vertex) = predecessorMap2Graph<SGraph<Key>, SVertex, Key>(p_map);
72 
73  LONGS_EQUAL(3, (long)boost::num_vertices(graph));
74  CHECK(root == key2vertex[2]);
75 }
76 
77 /* ************************************************************************* */
79 {
81  SharedNoiseModel cov = noiseModel::Unit::Create(3);
82  Pose2 p1(1.0, 2.0, 0.3), p2(4.0, 5.0, 0.6), p3(7.0, 8.0, 0.9), p4(2.0, 2.0, 2.9);
83  Pose2 p12=p1.between(p2), p23=p2.between(p3), p43=p4.between(p3);
84  graph += BetweenFactor<Pose2>(1,2, p12, cov);
85  graph += BetweenFactor<Pose2>(2,3, p23, cov);
86  graph += BetweenFactor<Pose2>(4,3, p43, cov);
87 
89  tree.insert(1,2);
90  tree.insert(2,2);
91  tree.insert(3,2);
92  tree.insert(4,3);
93 
94  Pose2 rootPose = p2;
95 
96  std::shared_ptr<Values> actual = composePoses<NonlinearFactorGraph, BetweenFactor<Pose2>, Pose2, Key> (graph, tree, rootPose);
97 
99  expected.insert(1, p1);
100  expected.insert(2, p2);
101  expected.insert(3, p3);
102  expected.insert(4, p4);
103 
104  LONGS_EQUAL(4, (long)actual->size());
105  CHECK(assert_equal(expected, *actual));
106 }
107 
108 /* ************************************************************************* */
110 {
112  Matrix I = I_2x2;
113  Vector2 b(0, 0);
114  const SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector2(0.5, 0.5));
115  using namespace symbol_shorthand;
116  g += JacobianFactor(X(1), I, X(2), I, b, model);
117  g += JacobianFactor(X(1), I, X(3), I, b, model);
118  g += JacobianFactor(X(1), I, X(4), I, b, model);
119  g += JacobianFactor(X(2), I, X(3), I, b, model);
120  g += JacobianFactor(X(2), I, X(4), I, b, model);
121  g += JacobianFactor(X(3), I, X(4), I, b, model);
122 
123  PredecessorMap<Key> tree = findMinimumSpanningTree<GaussianFactorGraph, Key, JacobianFactor>(g);
124  EXPECT_LONGS_EQUAL(X(1),tree[X(1)]);
125  EXPECT_LONGS_EQUAL(X(1),tree[X(2)]);
126  EXPECT_LONGS_EQUAL(X(1),tree[X(3)]);
127  EXPECT_LONGS_EQUAL(X(1),tree[X(4)]);
128 
129  // we add a disconnected component - does not work yet
130  // g += JacobianFactor(X(5), I, X(6), I, b, model);
131  //
132  // PredecessorMap<Key> forest = findMinimumSpanningTree<GaussianFactorGraph, Key, JacobianFactor>(g);
133  // EXPECT_LONGS_EQUAL(X(1),forest[X(1)]);
134  // EXPECT_LONGS_EQUAL(X(1),forest[X(2)]);
135  // EXPECT_LONGS_EQUAL(X(1),forest[X(3)]);
136  // EXPECT_LONGS_EQUAL(X(1),forest[X(4)]);
137  // EXPECT_LONGS_EQUAL(X(5),forest[X(5)]);
138  // EXPECT_LONGS_EQUAL(X(5),forest[X(6)]);
139 }
140 
142 // SL-FIX TEST( GaussianFactorGraph, split )
143 //{
144 // GaussianFactorGraph g;
145 // Matrix I = eye(2);
146 // Vector b = Vector_(0, 0, 0);
147 // g += X(1), I, X(2), I, b, model;
148 // g += X(1), I, X(3), I, b, model;
149 // g += X(1), I, X(4), I, b, model;
150 // g += X(2), I, X(3), I, b, model;
151 // g += X(2), I, X(4), I, b, model;
152 //
153 // PredecessorMap<string> tree;
154 // tree[X(1)] = X(1);
155 // tree[X(2)] = X(1);
156 // tree[X(3)] = X(1);
157 // tree[X(4)] = X(1);
158 //
159 // GaussianFactorGraph Ab1, Ab2;
160 // g.split<string, GaussianFactor>(tree, Ab1, Ab2);
161 // LONGS_EQUAL(3, Ab1.size());
162 // LONGS_EQUAL(2, Ab2.size());
163 //}
164 
166 // SL-FIX TEST( FactorGraph, splitMinimumSpanningTree )
167 //{
168 // SymbolicFactorGraph G;
169 // G.push_factor("x1", "x2");
170 // G.push_factor("x1", "x3");
171 // G.push_factor("x1", "x4");
172 // G.push_factor("x2", "x3");
173 // G.push_factor("x2", "x4");
174 // G.push_factor("x3", "x4");
175 //
176 // SymbolicFactorGraph T, C;
177 // std::tie(T, C) = G.splitMinimumSpanningTree();
178 //
179 // SymbolicFactorGraph expectedT, expectedC;
180 // expectedT.push_factor("x1", "x2");
181 // expectedT.push_factor("x1", "x3");
182 // expectedT.push_factor("x1", "x4");
183 // expectedC.push_factor("x2", "x3");
184 // expectedC.push_factor("x2", "x4");
185 // expectedC.push_factor("x3", "x4");
186 // CHECK(assert_equal(expectedT,T));
187 // CHECK(assert_equal(expectedC,C));
188 //}
189 
192 // * x1 - x2 - x3 - x4 - x5
193 // * | | / |
194 // * l1 l2 l3
195 // */
196 // SL-FIX TEST( FactorGraph, removeSingletons )
197 //{
198 // SymbolicFactorGraph G;
199 // G.push_factor("x1", "x2");
200 // G.push_factor("x2", "x3");
201 // G.push_factor("x3", "x4");
202 // G.push_factor("x4", "x5");
203 // G.push_factor("x2", "l1");
204 // G.push_factor("x3", "l2");
205 // G.push_factor("x4", "l2");
206 // G.push_factor("x4", "l3");
207 //
208 // SymbolicFactorGraph singletonGraph;
209 // set<Symbol> singletons;
210 // std::tie(singletonGraph, singletons) = G.removeSingletons();
211 //
212 // set<Symbol> singletons_excepted; singletons_excepted += "x1", "x2", "x5", "l1", "l3";
213 // CHECK(singletons_excepted == singletons);
214 //
215 // SymbolicFactorGraph singletonGraph_excepted;
216 // singletonGraph_excepted.push_factor("x2", "l1");
217 // singletonGraph_excepted.push_factor("x4", "l3");
218 // singletonGraph_excepted.push_factor("x1", "x2");
219 // singletonGraph_excepted.push_factor("x4", "x5");
220 // singletonGraph_excepted.push_factor("x2", "x3");
221 // CHECK(singletonGraph_excepted.equals(singletonGraph));
222 //}
223 
224 /* ************************************************************************* */
225 int main() {
226  TestResult tr;
227  return TestRegistry::runAllTests(tr);
228 }
229 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
Pose2.h
2D Pose
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::PredecessorMap::insert
void insert(const KEY &key, const KEY &parent)
Definition: graph.h:61
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:42
TestHarness.h
tree
Definition: testExpression.cpp:212
b
Scalar * b
Definition: benchVecAdd.cpp:17
gtsam::PredecessorMap
Definition: graph.h:58
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
TEST
TEST(Ordering, predecessorMap2Keys)
Definition: testGraph.cpp:40
X
#define X
Definition: icosphere.cpp:20
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::composePoses
std::shared_ptr< Values > composePoses(const G &graph, const PredecessorMap< KEY > &tree, const POSE &rootPose)
Definition: graph-inl.h:167
I
#define I
Definition: main.h:112
BetweenFactor.h
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::predecessorMap2Graph
std::tuple< G, V, std::map< KEY, V > > predecessorMap2Graph(const PredecessorMap< KEY > &p_map)
Definition: graph-inl.h:113
Symbol.h
simple::p3
static Point3 p3
Definition: testInitializePose3.cpp:53
Vector2
Definition: test_operator_overloading.cpp:18
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
gtsam::predecessorMap2Keys
std::list< KEY > predecessorMap2Keys(const PredecessorMap< KEY > &p_map)
Definition: graph-inl.h:50
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
p4
KeyInt p4(x4, 4)
TestResult
Definition: TestResult.h:26
JacobianFactor.h
main
int main()
Definition: testGraph.cpp:225
gtsam
traits
Definition: chartTesting.h:28
graph.h
Graph algorithm using boost library.
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
gtsam::SGraph
Definition: graph.h:46
CHECK
#define CHECK(condition)
Definition: Test.h:108
std
Definition: BFloat16.h:88
gtsam::SGraph::Vertex
boost::graph_traits< SGraph< KEY > >::vertex_descriptor Vertex
Definition: graph.h:49
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Graph
Definition: testGeneralSFMFactor.cpp:49
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::findMinimumSpanningTree
PredecessorMap< KEY > findMinimumSpanningTree(const G &fg)
Definition: graph-inl.h:222
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
LONGS_EQUAL
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:134
gtsam::Pose2
Definition: Pose2.h:39
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


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