benchCholesky.cpp
Go to the documentation of this file.
1 // g++ -DNDEBUG -O3 -I.. benchCholesky.cpp -o benchCholesky && ./benchCholesky
2 // options:
3 // -DBENCH_GSL -lgsl /usr/lib/libcblas.so.3
4 // -DEIGEN_DONT_VECTORIZE
5 // -msse2
6 // -DREPEAT=100
7 // -DTRIES=10
8 // -DSCALAR=double
9 
10 #include <iostream>
11 
12 #include <Eigen/Core>
13 #include <Eigen/Cholesky>
14 #include <bench/BenchUtil.h>
15 using namespace Eigen;
16 
17 #ifndef REPEAT
18 #define REPEAT 10000
19 #endif
20 
21 #ifndef TRIES
22 #define TRIES 10
23 #endif
24 
25 typedef float Scalar;
26 
27 template <typename MatrixType>
28 __attribute__ ((noinline)) void benchLLT(const MatrixType& m)
29 {
30  int rows = m.rows();
31  int cols = m.cols();
32 
33  double cost = 0;
34  for (int j=0; j<rows; ++j)
35  {
36  int r = std::max(rows - j -1,0);
37  cost += 2*(r*j+r+j);
38  }
39 
40  int repeats = (REPEAT*1000)/(rows*rows);
41 
42  typedef typename MatrixType::Scalar Scalar;
44 
45  MatrixType a = MatrixType::Random(rows,cols);
46  SquareMatrixType covMat = a * a.adjoint();
47 
48  BenchTimer timerNoSqrt, timerSqrt;
49 
50  Scalar acc = 0;
51  int r = internal::random<int>(0,covMat.rows()-1);
52  int c = internal::random<int>(0,covMat.cols()-1);
53  for (int t=0; t<TRIES; ++t)
54  {
55  timerNoSqrt.start();
56  for (int k=0; k<repeats; ++k)
57  {
58  LDLT<SquareMatrixType> cholnosqrt(covMat);
59  acc += cholnosqrt.matrixL().coeff(r,c);
60  }
61  timerNoSqrt.stop();
62  }
63 
64  for (int t=0; t<TRIES; ++t)
65  {
66  timerSqrt.start();
67  for (int k=0; k<repeats; ++k)
68  {
69  LLT<SquareMatrixType> chol(covMat);
70  acc += chol.matrixL().coeff(r,c);
71  }
72  timerSqrt.stop();
73  }
74 
75  if (MatrixType::RowsAtCompileTime==Dynamic)
76  std::cout << "dyn ";
77  else
78  std::cout << "fixed ";
79  std::cout << covMat.rows() << " \t"
80  << (timerNoSqrt.best()) / repeats << "s "
81  << "(" << 1e-9 * cost*repeats/timerNoSqrt.best() << " GFLOPS)\t"
82  << (timerSqrt.best()) / repeats << "s "
83  << "(" << 1e-9 * cost*repeats/timerSqrt.best() << " GFLOPS)\n";
84 
85 
86  #ifdef BENCH_GSL
87  if (MatrixType::RowsAtCompileTime==Dynamic)
88  {
89  timerSqrt.reset();
90 
91  gsl_matrix* gslCovMat = gsl_matrix_alloc(covMat.rows(),covMat.cols());
92  gsl_matrix* gslCopy = gsl_matrix_alloc(covMat.rows(),covMat.cols());
93 
94  eiToGsl(covMat, &gslCovMat);
95  for (int t=0; t<TRIES; ++t)
96  {
97  timerSqrt.start();
98  for (int k=0; k<repeats; ++k)
99  {
100  gsl_matrix_memcpy(gslCopy,gslCovMat);
101  gsl_linalg_cholesky_decomp(gslCopy);
102  acc += gsl_matrix_get(gslCopy,r,c);
103  }
104  timerSqrt.stop();
105  }
106 
107  std::cout << " | \t"
108  << timerSqrt.value() * REPEAT / repeats << "s";
109 
110  gsl_matrix_free(gslCovMat);
111  }
112  #endif
113  std::cout << "\n";
114  // make sure the compiler does not optimize too much
115  if (acc==123)
116  std::cout << acc;
117 }
118 
119 int main(int argc, char* argv[])
120 {
121  const int dynsizes[] = {4,6,8,16,24,32,49,64,128,256,512,900,1500,0};
122  std::cout << "size LDLT LLT";
123 // #ifdef BENCH_GSL
124 // std::cout << " GSL (standard + double + ATLAS) ";
125 // #endif
126  std::cout << "\n";
127  for (int i=0; dynsizes[i]>0; ++i)
128  benchLLT(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));
129 
130  benchLLT(Matrix<Scalar,2,2>());
131  benchLLT(Matrix<Scalar,3,3>());
132  benchLLT(Matrix<Scalar,4,4>());
133  benchLLT(Matrix<Scalar,5,5>());
134  benchLLT(Matrix<Scalar,6,6>());
135  benchLLT(Matrix<Scalar,7,7>());
136  benchLLT(Matrix<Scalar,8,8>());
137  benchLLT(Matrix<Scalar,12,12>());
138  benchLLT(Matrix<Scalar,16,16>());
139  return 0;
140 }
141 
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
MatrixType
MatrixXf MatrixType
Definition: benchmark-blocking-sizes.cpp:52
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
__attribute__
__attribute__((noinline)) void benchLLT(const MatrixType &m)
Definition: benchCholesky.cpp:28
main
int main(int argc, char *argv[])
Definition: benchCholesky.cpp:119
rows
int rows
Definition: Tutorial_commainit_02.cpp:1
Scalar
float Scalar
Definition: benchCholesky.cpp:25
Eigen::BenchTimer::value
double value(int TIMER=CPU_TIMER) const
Definition: BenchTimer.h:104
BenchUtil.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Eigen::LDLT::matrixL
Traits::MatrixL matrixL() const
Definition: LDLT.h:156
Eigen::BenchTimer::start
void start()
Definition: BenchTimer.h:81
Eigen::LLT::matrixL
Traits::MatrixL matrixL() const
Definition: LLT.h:135
Eigen::Dynamic
const int Dynamic
Definition: Constants.h:22
Eigen::BenchTimer
Definition: BenchTimer.h:59
REPEAT
#define REPEAT
Definition: benchCholesky.cpp:18
Eigen::LDLT
Robust Cholesky decomposition of a matrix with pivoting.
Definition: LDLT.h:59
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
Eigen::BenchTimer::reset
void reset()
Definition: BenchTimer.h:75
TRIES
#define TRIES
Definition: benchCholesky.cpp:22
Eigen::LLT
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
Definition: LLT.h:66
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
Eigen::BenchTimer::best
double best(int TIMER=CPU_TIMER) const
Definition: BenchTimer.h:111
Eigen::BenchTimer::stop
void stop()
Definition: BenchTimer.h:86
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
cols
int cols
Definition: Tutorial_commainit_02.cpp:1
align_3::t
Point2 t(10, 10)
max
#define max(a, b)
Definition: datatypes.h:20
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:01:47