testSubgraphPreconditioner.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 <tests/smallExample.h>
19 
22 #include <gtsam/inference/Symbol.h>
26 #include <gtsam/linear/iterative.h>
27 #include <gtsam/slam/dataset.h>
29 
31 
32 #include <boost/archive/xml_iarchive.hpp>
33 #include <boost/assign/std/list.hpp>
34 #include <boost/range/adaptor/reversed.hpp>
35 #include <boost/serialization/export.hpp>
36 #include <boost/tuple/tuple.hpp>
37 using namespace boost::assign;
38 
39 #include <fstream>
40 
41 using namespace std;
42 using namespace gtsam;
43 using namespace example;
44 
45 // define keys
46 // Create key for simulated planar graph
47 Symbol key(int x, int y) { return symbol_shorthand::X(1000 * x + y); }
48 
49 /* ************************************************************************* */
51  // Check canonical ordering
53  expected +=
54  key(3, 3), key(2, 3), key(1, 3),
55  key(3, 2), key(2, 2), key(1, 2),
56  key(3, 1), key(2, 1), key(1, 1);
57  EXPECT(assert_equal(expected, ordering));
58 }
59 
60 /* ************************************************************************* */
62 static double error(const GaussianFactorGraph& fg, const VectorValues& x) {
63  double total_error = 0.;
64  for (const GaussianFactor::shared_ptr& factor : fg)
65  total_error += factor->error(x);
66  return total_error;
67 }
68 
69 /* ************************************************************************* */
71  // Check planar graph construction
73  VectorValues xtrue;
74  boost::tie(A, xtrue) = planarGraph(3);
75  LONGS_EQUAL(13, A.size());
76  LONGS_EQUAL(9, xtrue.size());
77  DOUBLES_EQUAL(0, error(A, xtrue), 1e-9); // check zero error for xtrue
78 
79  // Check that xtrue is optimal
81  VectorValues actual = R1->optimize();
82  EXPECT(assert_equal(xtrue, actual));
83 }
84 
85 /* ************************************************************************* */
87  // Build a planar graph
89  VectorValues xtrue;
90  boost::tie(A, xtrue) = planarGraph(3);
91 
92  // Get the spanning tree and constraints, and check their sizes
94  boost::tie(T, C) = splitOffPlanarTree(3, A);
95  LONGS_EQUAL(9, T->size());
96  LONGS_EQUAL(4, C->size());
97 
98  // Check that the tree can be solved to give the ground xtrue
99  GaussianBayesNet::shared_ptr R1 = T->eliminateSequential();
100  VectorValues xbar = R1->optimize();
101  EXPECT(assert_equal(xtrue, xbar));
102 }
103 
104 /* ************************************************************************* */
106  // Build a planar graph
108  VectorValues xtrue;
109  size_t N = 3;
110  boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b
111 
112  // Get the spanning tree and remaining graph
113  GaussianFactorGraph::shared_ptr Ab1, Ab2; // A1*x-b1 and A2*x-b2
114  boost::tie(Ab1, Ab2) = splitOffPlanarTree(N, Ab);
115 
116  // Eliminate the spanning tree to build a prior
117  const Ordering ord = planarOrdering(N);
118  auto Rc1 = Ab1->eliminateSequential(ord); // R1*x-c1
119  VectorValues xbar = Rc1->optimize(); // xbar = inv(R1)*c1
120 
121  // Create Subgraph-preconditioned system
122  VectorValues::shared_ptr xbarShared(
123  new VectorValues(xbar)); // TODO: horrible
124  const SubgraphPreconditioner system(Ab2, Rc1, xbarShared);
125 
126  // Get corresponding matrices for tests. Add dummy factors to Ab2 to make
127  // sure it works with the ordering.
128  Ordering ordering = Rc1->ordering(); // not ord in general!
129  Ab2->add(key(1, 1), Z_2x2, Z_2x1);
130  Ab2->add(key(1, 2), Z_2x2, Z_2x1);
131  Ab2->add(key(1, 3), Z_2x2, Z_2x1);
132  Matrix A, A1, A2;
133  Vector b, b1, b2;
134  std::tie(A, b) = Ab.jacobian(ordering);
135  std::tie(A1, b1) = Ab1->jacobian(ordering);
136  std::tie(A2, b2) = Ab2->jacobian(ordering);
137  Matrix R1 = Rc1->matrix(ordering).first;
138  Matrix Abar(13 * 2, 9 * 2);
139  Abar.topRows(9 * 2) = Matrix::Identity(9 * 2, 9 * 2);
140  Abar.bottomRows(8) = A2.topRows(8) * R1.inverse();
141 
142  // Helper function to vectorize in correct order, which is the order in which
143  // we eliminated the spanning tree.
144  auto vec = [ordering](const VectorValues& x) { return x.vector(ordering); };
145 
146  // Set up y0 as all zeros
147  const VectorValues y0 = system.zero();
148 
149  // y1 = perturbed y0
150  VectorValues y1 = system.zero();
151  y1[key(3, 3)] = Vector2(1.0, -1.0);
152 
153  // Check backSubstituteTranspose works with R1
154  VectorValues actual = Rc1->backSubstituteTranspose(y1);
155  Vector expected = R1.transpose().inverse() * vec(y1);
156  EXPECT(assert_equal(expected, vec(actual)));
157 
158  // Check corresponding x values
159  // for y = 0, we get xbar:
160  EXPECT(assert_equal(xbar, system.x(y0)));
161  // for non-zero y, answer is x = xbar + inv(R1)*y
162  const Vector expected_x1 = vec(xbar) + R1.inverse() * vec(y1);
163  const VectorValues x1 = system.x(y1);
164  EXPECT(assert_equal(expected_x1, vec(x1)));
165 
166  // Check errors
167  DOUBLES_EQUAL(0, error(Ab, xbar), 1e-9);
168  DOUBLES_EQUAL(0, system.error(y0), 1e-9);
169  DOUBLES_EQUAL(2, error(Ab, x1), 1e-9);
170  DOUBLES_EQUAL(2, system.error(y1), 1e-9);
171 
172  // Check that transposeMultiplyAdd <=> y += alpha * Abar' * e
173  // We check for e1 =[1;0] and e2=[0;1] corresponding to T and C
174  const double alpha = 0.5;
175  Errors e1, e2;
176  for (size_t i = 0; i < 13; i++) {
177  e1 += i < 9 ? Vector2(1, 1) : Vector2(0, 0);
178  e2 += i >= 9 ? Vector2(1, 1) : Vector2(0, 0);
179  }
180  Vector ee1(13 * 2), ee2(13 * 2);
181  ee1 << Vector::Ones(9 * 2), Vector::Zero(4 * 2);
182  ee2 << Vector::Zero(9 * 2), Vector::Ones(4 * 2);
183 
184  // Check transposeMultiplyAdd for e1
185  VectorValues y = system.zero();
186  system.transposeMultiplyAdd(alpha, e1, y);
187  Vector expected_y = alpha * Abar.transpose() * ee1;
188  EXPECT(assert_equal(expected_y, vec(y)));
189 
190  // Check transposeMultiplyAdd for e2
191  y = system.zero();
192  system.transposeMultiplyAdd(alpha, e2, y);
193  expected_y = alpha * Abar.transpose() * ee2;
194  EXPECT(assert_equal(expected_y, vec(y)));
195 
196  // Test gradient in y
197  auto g = system.gradient(y0);
198  Vector expected_g = Vector::Zero(18);
199  EXPECT(assert_equal(expected_g, vec(g)));
200 }
201 
202 /* ************************************************************************* */
204 
205 // Read from XML file
206 static GaussianFactorGraph read(const string& name) {
207  auto inputFile = findExampleDataFile(name);
208  ifstream is(inputFile);
209  if (!is.is_open()) throw runtime_error("Cannot find file " + inputFile);
210  boost::archive::xml_iarchive in_archive(is);
212  in_archive >> boost::serialization::make_nvp("graph", Ab);
213  return Ab;
214 }
215 
217  // Create preconditioner
218  SubgraphPreconditioner system;
219 
220  // We test on three different graphs
221  const auto Ab1 = planarGraph(3).first;
222  const auto Ab2 = read("toy3D");
223  const auto Ab3 = read("randomGrid3D");
224 
225  // For all graphs, test solve and solveTranspose
226  for (const auto& Ab : {Ab1, Ab2, Ab3}) {
227  // Call build, a non-const method needed to make solve work :-(
228  KeyInfo keyInfo(Ab);
229  std::map<Key, Vector> lambda;
230  system.build(Ab, keyInfo, lambda);
231 
232  // Create a perturbed (non-zero) RHS
233  const auto xbar = system.Rc1()->optimize(); // merely for use in zero below
234  auto values_y = VectorValues::Zero(xbar);
235  auto it = values_y.begin();
236  it->second.setConstant(100);
237  ++it;
238  it->second.setConstant(-100);
239 
240  // Solve the VectorValues way
241  auto values_x = system.Rc1()->backSubstitute(values_y);
242 
243  // Solve the matrix way, this really just checks BN::backSubstitute
244  // This only works with Rc1 ordering, not with keyInfo !
245  // TODO(frank): why does this not work with an arbitrary ordering?
246  const auto ord = system.Rc1()->ordering();
247  const Matrix R1 = system.Rc1()->matrix(ord).first;
248  auto ord_y = values_y.vector(ord);
249  auto vector_x = R1.inverse() * ord_y;
250  EXPECT(assert_equal(vector_x, values_x.vector(ord)));
251 
252  // Test that 'solve' does implement x = R^{-1} y
253  // We do this by asserting it gives same answer as backSubstitute
254  // Only works with keyInfo ordering:
255  const auto ordering = keyInfo.ordering();
256  auto vector_y = values_y.vector(ordering);
257  const size_t N = R1.cols();
258  Vector solve_x = Vector::Zero(N);
259  system.solve(vector_y, solve_x);
260  EXPECT(assert_equal(values_x.vector(ordering), solve_x));
261 
262  // Test that transposeSolve does implement x = R^{-T} y
263  // We do this by asserting it gives same answer as backSubstituteTranspose
264  auto values_x2 = system.Rc1()->backSubstituteTranspose(values_y);
265  Vector solveT_x = Vector::Zero(N);
266  system.transposeSolve(vector_y, solveT_x);
267  EXPECT(assert_equal(values_x2.vector(ordering), solveT_x));
268  }
269 }
270 
271 /* ************************************************************************* */
273  // Build a planar graph
275  VectorValues xtrue;
276  size_t N = 3;
277  boost::tie(Ab, xtrue) = planarGraph(N); // A*x-b
278 
279  // Get the spanning tree
280  GaussianFactorGraph::shared_ptr Ab1, Ab2; // A1*x-b1 and A2*x-b2
281  boost::tie(Ab1, Ab2) = splitOffPlanarTree(N, Ab);
282 
283  // Eliminate the spanning tree to build a prior
285  Ab1->eliminateSequential(); // R1*x-c1
286  VectorValues xbar = Rc1->optimize(); // xbar = inv(R1)*c1
287 
288  // Create Subgraph-preconditioned system
289  VectorValues::shared_ptr xbarShared(
290  new VectorValues(xbar)); // TODO: horrible
291  SubgraphPreconditioner system(Ab2, Rc1, xbarShared);
292 
293  // Create zero config y0 and perturbed config y1
294  VectorValues y0 = VectorValues::Zero(xbar);
295 
296  VectorValues y1 = y0;
297  y1[key(2, 2)] = Vector2(1.0, -1.0);
298  VectorValues x1 = system.x(y1);
299 
300  // Solve for the remaining constraints using PCG
303  VectorValues, Errors>(system, y1, parameters);
304  EXPECT(assert_equal(y0,actual));
305 
306  // Compare with non preconditioned version:
307  VectorValues actual2 = conjugateGradientDescent(Ab, x1, parameters);
308  EXPECT(assert_equal(xtrue, actual2, 1e-4));
309 }
310 
311 /* ************************************************************************* */
312 int main() {
313  TestResult tr;
314  return TestRegistry::runAllTests(tr);
315 }
316 /* ************************************************************************* */
size_t size() const
Definition: FactorGraph.h:306
void build(const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map< Key, Vector > &lambda) override
build/factorize the preconditioner
Scalar * y
Scalar * b
Definition: benchVecAdd.cpp:17
static int runAllTests(TestResult &result)
static GaussianFactorGraph read(const string &name)
VectorValues x(const VectorValues &y) const
static enum @843 ordering
double error(const VectorValues &y) const
Matrix expected
Definition: testMatrix.cpp:974
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor,"JacobianFactor")
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: VectorValues.h:83
Iterative methods, implementation.
size_t size() const
Definition: VectorValues.h:125
Definition: Half.h:150
boost::shared_ptr< const GaussianBayesNet > sharedBayesNet
Some functions to compute numerical derivatives.
V conjugateGradients(const S &Ab, V x, const ConjugateGradientParameters &parameters, bool steepest)
boost::shared_ptr< This > shared_ptr
const Ordering & ordering() const
Return the ordering.
#define N
Definition: gksort.c:12
VectorValues gradient(const VectorValues &y) const
void g(const string &key, int i)
Definition: testBTree.cpp:43
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
static double error(const GaussianFactorGraph &fg, const VectorValues &x)
EIGEN_DEVICE_FUNC RotationMatrixType matrix() const
Definition: RotationBase.h:50
string inputFile
Eigen::VectorXd Vector
Definition: Vector.h:38
const sharedBayesNet & Rc1() const
#define EXPECT(condition)
Definition: Test.h:151
Vector2 b2(4,-5)
Eigen::Triplet< double > T
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
void transposeSolve(const Vector &y, Vector &x) const override
implement x = R^{-T} y
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
TEST(SubgraphPreconditioner, planarOrdering)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static ConjugateGradientParameters parameters
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
std::pair< Matrix, Vector > jacobian(const Ordering &ordering) const
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
#define LONGS_EQUAL(expected, actual)
Definition: Test.h:135
Ordering planarOrdering(size_t N)
Definition: smallExample.h:673
void transposeMultiplyAdd(double alpha, const Errors &e, VectorValues &y) const
traits
Definition: chartTesting.h:28
std::pair< GaussianFactorGraph, VectorValues > planarGraph(size_t N)
Definition: smallExample.h:631
Vector2 b1(2,-1)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Vector conjugateGradientDescent(const System &Ab, const Vector &x, const ConjugateGradientParameters &parameters)
Definition: iterative.cpp:45
Eigen::Vector2d Vector2
Definition: Vector.h:42
std::pair< GaussianFactorGraph::shared_ptr, GaussianFactorGraph::shared_ptr > splitOffPlanarTree(size_t N, const GaussianFactorGraph &original)
Definition: smallExample.h:682
Pose3 x1
Definition: testPose3.cpp:588
Create small example with two poses and one landmark.
boost::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
Annotation for function names.
Definition: attr.h:36
#define X
Definition: icosphere.cpp:20
void solve(const Vector &y, Vector &x) const override
implement x = R^{-1} y
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
utility functions for loading datasets
Symbol key(int x, int y)
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
Definition: Vector.h:45


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