testSubgraphSolver.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 
19 
20 #include <tests/smallExample.h>
22 #include <gtsam/linear/iterative.h>
25 #include <gtsam/inference/Symbol.h>
28 
30 
31 #include <boost/assign/std/list.hpp>
32 using namespace boost::assign;
33 
34 using namespace std;
35 using namespace gtsam;
36 
37 static size_t N = 3;
40 
41 /* ************************************************************************* */
43 static double error(const GaussianFactorGraph& fg, const VectorValues& x) {
44  double total_error = 0.;
45  for(const GaussianFactor::shared_ptr& factor: fg)
46  total_error += factor->error(x);
47  return total_error;
48 }
49 
50 /* ************************************************************************* */
51 TEST( SubgraphSolver, Parameters )
52 {
53  LONGS_EQUAL(SubgraphSolverParameters::SILENT, kParameters.verbosity());
54  LONGS_EQUAL(500, kParameters.maxIterations());
55 }
56 
57 /* ************************************************************************* */
59 {
60  // Build a planar graph
62  VectorValues xtrue;
63  std::tie(Ab, xtrue) = example::planarGraph(N); // A*x-b
64 
66  params.augmentationFactor = 0.0;
67  SubgraphBuilder builder(params);
68  auto subgraph = builder(Ab);
69  EXPECT_LONGS_EQUAL(9, subgraph.size());
70 
72  std::tie(Ab1, Ab2) = splitFactorGraph(Ab, subgraph);
73  EXPECT_LONGS_EQUAL(9, Ab1->size());
74  EXPECT_LONGS_EQUAL(13, Ab2->size());
75 }
76 
77 /* ************************************************************************* */
78 TEST( SubgraphSolver, constructor1 )
79 {
80  // Build a planar graph
82  VectorValues xtrue;
83  std::tie(Ab, xtrue) = example::planarGraph(N); // A*x-b
84 
85  // The first constructor just takes a factor graph (and kParameters)
86  // and it will split the graph into A1 and A2, where A1 is a spanning tree
87  SubgraphSolver solver(Ab, kParameters, kOrdering);
88  VectorValues optimized = solver.optimize(); // does PCG optimization
89  DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5);
90 }
91 
92 /* ************************************************************************* */
93 TEST( SubgraphSolver, constructor2 )
94 {
95  // Build a planar graph
97  VectorValues xtrue;
98  size_t N = 3;
99  std::tie(Ab, xtrue) = example::planarGraph(N); // A*x-b
100 
101  // Get the spanning tree
102  GaussianFactorGraph::shared_ptr Ab1, Ab2; // A1*x-b1 and A2*x-b2
103  std::tie(Ab1, Ab2) = example::splitOffPlanarTree(N, Ab);
104 
105  // The second constructor takes two factor graphs, so the caller can specify
106  // the preconditioner (Ab1) and the constraints that are left out (Ab2)
107  SubgraphSolver solver(*Ab1, Ab2, kParameters, kOrdering);
108  VectorValues optimized = solver.optimize();
109  DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5);
110 }
111 
112 /* ************************************************************************* */
113 TEST( SubgraphSolver, constructor3 )
114 {
115  // Build a planar graph
117  VectorValues xtrue;
118  size_t N = 3;
119  std::tie(Ab, xtrue) = example::planarGraph(N); // A*x-b
120 
121  // Get the spanning tree and corresponding kOrdering
122  GaussianFactorGraph::shared_ptr Ab1, Ab2; // A1*x-b1 and A2*x-b2
123  std::tie(Ab1, Ab2) = example::splitOffPlanarTree(N, Ab);
124 
125  // The caller solves |A1*x-b1|^2 == |R1*x-c1|^2, where R1 is square UT
126  auto Rc1 = Ab1->eliminateSequential();
127 
128  // The third constructor allows the caller to pass an already solved preconditioner Rc1_
129  // as a Bayes net, in addition to the "loop closing constraints" Ab2, as before
130  SubgraphSolver solver(Rc1, Ab2, kParameters);
131  VectorValues optimized = solver.optimize();
132  DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5);
133 }
134 
135 /* ************************************************************************* */
136 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
137 /* ************************************************************************* */
TEST(SubgraphSolver, Parameters)
static int runAllTests(TestResult &result)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Subgraph Solver from IROS 2010.
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
Iterative methods, implementation.
Definition: Half.h:150
BiCGSTAB< SparseMatrix< double > > solver
Some functions to compute numerical derivatives.
std::pair< GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitFactorGraph(const GaussianFactorGraph &factorGraph, const Subgraph &subgraph)
int main()
double augmentationFactor
factor multiplied with n, yields number of extra edges.
static size_t N
static double error(const GaussianFactorGraph &fg, const VectorValues &x)
static SubgraphSolverParameters kParameters
static auto kOrdering
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues optimize() const
Optimize from zero.
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
Ordering planarOrdering(size_t N)
Definition: smallExample.h:673
traits
Definition: chartTesting.h:28
std::pair< GaussianFactorGraph, VectorValues > planarGraph(size_t N)
Definition: smallExample.h:631
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
std::pair< GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitOffPlanarTree(size_t N, const GaussianFactorGraph &original)
Definition: smallExample.h:682
Create small example with two poses and one landmark.
Chordal Bayes Net, the result of eliminating a factor graph.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:57