timeSchurFactors.cpp
Go to the documentation of this file.
1 
8 #include "DummyFactor.h"
9 #include <gtsam/base/timing.h>
10 
16 
17 #include <boost/assign/list_of.hpp>
18 #include <boost/assign/std/vector.hpp>
19 #include <fstream>
20 
21 using namespace std;
22 using namespace boost::assign;
23 using namespace gtsam;
24 
25 #define SLOW
26 #define RAW
27 #define HESSIAN
28 #define NUM_ITERATIONS 1000
29 
30 // Create CSV file for results
31 ofstream os("timeSchurFactors.csv");
32 
33 /*************************************************************************************/
34 template<typename CAMERA>
35 void timeAll(size_t m, size_t N) {
36 
37  cout << m << endl;
38 
39  // create F
40  static const int D = CAMERA::dimension;
41  typedef Eigen::Matrix<double, 2, D> Matrix2D;
43  vector <Matrix2D, Eigen::aligned_allocator<Matrix2D>> Fblocks;
44  for (size_t i = 0; i < m; i++) {
45  keys.push_back(i);
46  Fblocks.push_back((i + 1) * Matrix::Ones(2, D));
47  }
48 
49  // create E
50  Matrix E(2 * m, 3);
51  for (size_t i = 0; i < m; i++)
52  E.block < 2, 3 > (2 * i, 0) = Matrix::Ones(2, 3);
53 
54  // Calculate point covariance
55  Matrix P = (E.transpose() * E).inverse();
56 
57  // RHS and sigmas
58  const Vector b = Vector::Constant(2*m,1);
59  const SharedDiagonal model;
60 
61  // parameters for multiplyHessianAdd
62  double alpha = 0.5;
63  VectorValues xvalues, yvalues;
64  for (size_t i = 0; i < m; i++)
65  xvalues.insert(i, Vector::Constant(D,2));
66 
67  // Implicit
68  RegularImplicitSchurFactor<CAMERA> implicitFactor(keys, Fblocks, E, P, b);
69  // JacobianFactor with same error
70  JacobianFactorQ<D, 2> jf(keys, Fblocks, E, P, b, model);
71  // JacobianFactorQR with same error
72  JacobianFactorQR<D, 2> jqr(keys, Fblocks, E, P, b, model);
73  // Hessian
74  HessianFactor hessianFactor(jqr);
75 
76 #define TIME(label,factor,xx,yy) {\
77  for (size_t t = 0; t < N; t++) \
78  factor.multiplyHessianAdd(alpha, xx, yy);\
79  gttic_(label);\
80  for (size_t t = 0; t < N; t++) {\
81  factor.multiplyHessianAdd(alpha, xx, yy);\
82  }\
83  gttoc_(label);\
84  tictoc_getNode(timer, label)\
85  os << timer->secs()/NUM_ITERATIONS << ", ";\
86  }
87 
88 #ifdef SLOW
89  TIME(Implicit, implicitFactor, xvalues, yvalues)
90  TIME(Jacobian, jf, xvalues, yvalues)
91  TIME(JacobianQR, jqr, xvalues, yvalues)
92 #endif
93 
94 #ifdef HESSIAN
95  TIME(Hessian, hessianFactor, xvalues, yvalues)
96 #endif
97 
98 #ifdef OVERHEAD
99  DummyFactor<D> dummy(Fblocks, E, P, b);
100  TIME(Overhead,dummy,xvalues,yvalues)
101 #endif
102 
103 #ifdef RAW
104  { // Raw memory Version
106  for (size_t i = 0; i < m; i++)
107  keys += i;
108  Vector x = xvalues.vector(keys);
109  double* xdata = x.data();
110 
111  // create a y
112  Vector y = Vector::Zero(m * D);
113  TIME(RawImplicit, implicitFactor, xdata, y.data())
114  TIME(RawJacobianQ, jf, xdata, y.data())
115  TIME(RawJacobianQR, jqr, xdata, y.data())
116  }
117 #endif
118 
119  os << m << endl;
120 
121 } // timeAll
122 
123 /*************************************************************************************/
124 int main(void) {
125 #ifdef SLOW
126  os << "Implicit,";
127  os << "JacobianQ,";
128  os << "JacobianQR,";
129 #endif
130 #ifdef HESSIAN
131  os << "Hessian,";
132 #endif
133 #ifdef OVERHEAD
134  os << "Overhead,";
135 #endif
136 #ifdef RAW
137  os << "RawImplicit,";
138  os << "RawJacobianQ,";
139  os << "RawJacobianQR,";
140 #endif
141  os << "m" << endl;
142  // define images
143  vector < size_t > ms;
144  // ms += 2;
145  // ms += 3, 4, 5, 6, 7, 8, 9, 10;
146  // ms += 11,12,13,14,15,16,17,18,19;
147  // ms += 20, 30, 40, 50;
148  // ms += 20,30,40,50,60,70,80,90,100;
149  for (size_t m = 2; m <= 50; m += 2)
150  ms += m;
151  //for (size_t m=10;m<=100;m+=10) ms += m;
152  // loop over number of images
153  for(size_t m: ms)
154  timeAll<PinholePose<Cal3Bundler> >(m, NUM_ITERATIONS);
155 }
156 
157 //*************************************************************************************
Matrix3f m
Pinhole camera with known calibration.
Key E(std::uint64_t j)
Scalar * y
Scalar * b
Definition: benchVecAdd.cpp:17
noiseModel::Diagonal::shared_ptr model
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
static const double ms
#define N
Definition: gksort.c:12
int main(void)
#define NUM_ITERATIONS
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Eigen::VectorXd Vector
Definition: Vector.h:38
RealScalar alpha
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
#define TIME(label, factor, xx, yy)
ofstream os("timeSchurFactors.csv")
void timeAll(size_t m, size_t N)
A Gaussian factor using the canonical parameters (information form)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
const KeyVector keys
The matrix class, also used for vectors and row-vectors.
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
iterator insert(const std::pair< Key, Vector > &key_value)
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Calibration used by Bundler.
Timing utilities.
Vector vector() const


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