timeFactorOverhead.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 #include <gtsam/base/timing.h>
24 
25 #include <random>
26 #include <vector>
27 
28 using namespace gtsam;
29 using namespace std;
30 
31 static std::mt19937 rng;
32 static std::uniform_real_distribution<> uniform(0.0, 1.0);
33 
34 int main(int argc, char *argv[]) {
35 
36  Key key = 0;
37 
38  size_t vardim = 2;
39  size_t blockdim = 1;
40  size_t nBlocks = 4000;
41 
42  size_t nTrials = 20;
43 
44  double blockbuild, blocksolve, combbuild, combsolve;
45 
46  cout << "\n1 variable of dimension " << vardim << ", " <<
47  nBlocks << " blocks of dimension " << blockdim << "\n";
48  cout << nTrials << " trials\n";
49 
51  // Timing test with blockwise Gaussian factor graphs
52 
53  {
54  // Build GFG's
55  cout << "Building blockwise Gaussian factor graphs... ";
56  cout.flush();
57  gttic_(blockbuild);
58  vector<GaussianFactorGraph> blockGfgs;
59  blockGfgs.reserve(nTrials);
60  for(size_t trial=0; trial<nTrials; ++trial) {
61  blockGfgs.push_back(GaussianFactorGraph());
62  SharedDiagonal noise = noiseModel::Isotropic::Sigma(blockdim, 1.0);
63  for(size_t i=0; i<nBlocks; ++i) {
64  // Generate a random Gaussian factor
65  Matrix A(blockdim, vardim);
66  for(size_t j=0; j<blockdim; ++j)
67  for(size_t k=0; k<vardim; ++k)
68  A(j,k) = uniform(rng);
69  Vector b(blockdim);
70  for(size_t j=0; j<blockdim; ++j)
71  b(j) = uniform(rng);
72  blockGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, A, b, noise));
73  }
74  }
75  gttoc_(blockbuild);
76  tictoc_getNode(blockbuildNode, blockbuild);
77  blockbuild = blockbuildNode->secs();
78  cout << blockbuild << " s" << endl;
79 
80  // Solve GFG's
81  cout << "Solving blockwise Gaussian factor graphs... ";
82  cout.flush();
83  gttic_(blocksolve);
84  for(size_t trial=0; trial<nTrials; ++trial) {
85 // cout << "Trial " << trial << endl;
86  GaussianBayesNet::shared_ptr gbn = blockGfgs[trial].eliminateSequential();
87  VectorValues soln = gbn->optimize();
88  }
89  gttoc_(blocksolve);
90  tictoc_getNode(blocksolveNode, blocksolve);
91  blocksolve = blocksolveNode->secs();
92  cout << blocksolve << " s" << endl;
93  }
94 
95 
97  // Timing test with combined-factor Gaussian factor graphs
98 
99  {
100  // Build GFG's
101  cout << "Building combined-factor Gaussian factor graphs... ";
102  cout.flush();
103  gttic_(combbuild);
104  vector<GaussianFactorGraph> combGfgs;
105  for(size_t trial=0; trial<nTrials; ++trial) {
106  combGfgs.push_back(GaussianFactorGraph());
107  SharedDiagonal noise = noiseModel::Isotropic::Sigma(blockdim, 1.0);
108 
109  Matrix Acomb(blockdim*nBlocks, vardim);
110  Vector bcomb(blockdim*nBlocks);
111  for(size_t i=0; i<nBlocks; ++i) {
112  // Generate a random Gaussian factor
113  for(size_t j=0; j<blockdim; ++j)
114  for(size_t k=0; k<vardim; ++k)
115  Acomb(blockdim*i+j, k) = uniform(rng);
116  Vector b(blockdim);
117  for(size_t j=0; j<blockdim; ++j)
118  bcomb(blockdim*i+j) = uniform(rng);
119  }
120  combGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, Acomb, bcomb,
121  noiseModel::Isotropic::Sigma(blockdim*nBlocks, 1.0)));
122  }
123  gttoc(combbuild);
124  tictoc_getNode(combbuildNode, combbuild);
125  combbuild = combbuildNode->secs();
126  cout << combbuild << " s" << endl;
127 
128  // Solve GFG's
129  cout << "Solving combined-factor Gaussian factor graphs... ";
130  cout.flush();
131  gttic_(combsolve);
132  for(size_t trial=0; trial<nTrials; ++trial) {
133  GaussianBayesNet::shared_ptr gbn = combGfgs[trial].eliminateSequential();
134  VectorValues soln = gbn->optimize();
135  }
136  gttoc_(combsolve);
137  tictoc_getNode(combsolveNode, combsolve);
138  combsolve = combsolveNode->secs();
139  cout << combsolve << " s" << endl;
140  }
141 
143  // Print per-graph times
144  cout << "\nPer-factor-graph times for building and solving\n";
145  cout << "Blockwise: total " << (1000.0*(blockbuild+blocksolve)/double(nTrials)) <<
146  " build " << (1000.0*blockbuild/double(nTrials)) <<
147  " solve " << (1000.0*blocksolve/double(nTrials)) << " ms/graph\n";
148  cout << "Combined: total " << (1000.0*(combbuild+combsolve)/double(nTrials)) <<
149  " build " << (1000.0*combbuild/double(nTrials)) <<
150  " solve " << (1000.0*combsolve/double(nTrials)) << " ms/graph\n";
151  cout << "Fraction of time spent in overhead\n" <<
152  " total " << (((blockbuild+blocksolve)-(combbuild+combsolve)) / (blockbuild+blocksolve)) << "\n" <<
153  " build " << ((blockbuild-combbuild) / blockbuild) << "\n" <<
154  " solve " << ((blocksolve-combsolve) / blocksolve) << "\n";
155  cout << endl;
156 
157  return 0;
158 }
159 
#define tictoc_getNode(variable, label)
Definition: timing.h:261
#define gttic_(label)
Definition: timing.h:230
static std::uniform_real_distribution uniform(0.0, 1.0)
int main(int argc, char *argv[])
static std::mt19937 rng
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
boost::shared_ptr< This > shared_ptr
Factor Graph Values.
Eigen::VectorXd Vector
Definition: Vector.h:38
Linear Factor Graph where all factors are Gaussians.
const G & b
Definition: Group.h:83
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
#define gttoc(label)
Definition: timing.h:281
Chordal Bayes Net, the result of eliminating a factor graph.
#define gttoc_(label)
Definition: timing.h:235
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
std::ptrdiff_t j
Timing utilities.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:33