4 #include <Eigen/Sparse> 26 #define MINDENSITY 0.0004 35 for (int _j=0; _j<NBTRIES; ++_j) { \ 37 for (int _k=0; _k<REPEAT; ++_k) { \ 46 dst.startFill(rows*cols*density);
49 dst.fill(
j,
j) = internal::random<Scalar>(10,20);
52 Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;
61 #include <Eigen/Cholesky> 66 std::cout << name <<
"..." << std::flush;
69 SparseLLT<EigenSparseSelfAdjointMatrix,Backend> chol(sm1, flags);
71 std::cout <<
":\t" << timer.
value() << endl;
73 std::cout <<
" nnz: " << sm1.
nonZeros() <<
" => " << chol.matrixL().nonZeros() <<
"\n";
77 int main(
int argc,
char *argv[])
84 VectorXf
b = VectorXf::Random(cols);
85 VectorXf
x = VectorXf::Random(cols);
87 bool densedone =
false;
93 std::cout <<
"Generate sparse matrix (might take a while)...\n";
95 std::cout <<
"DONE\n\n";
102 std::cout <<
"Eigen Dense\t" << density*100 <<
"%\n";
105 m1 = (m1 + m1.transpose()).
eval();
106 m1.diagonal() *= 0.5;
115 std::cout <<
"dense:\t" << timer.
value() << endl;
121 std::cout <<
"dense: " <<
"nnz = " << count <<
"\n";
127 doEigen<Eigen::DefaultBackend>(
"Eigen/Sparse", sm1, Eigen::IncompleteFactorization);
129 #ifdef EIGEN_CHOLMOD_SUPPORT 130 doEigen<Eigen::Cholmod>(
"Eigen/Cholmod", sm1, Eigen::IncompleteFactorization);
133 #ifdef EIGEN_TAUCS_SUPPORT 134 doEigen<Eigen::Taucs>(
"Eigen/Taucs", sm1, Eigen::IncompleteFactorization);
140 taucs_ccs_matrix
A = sm1.asTaucsMatrix();
146 taucs_ccs_matrix* chol = taucs_ccs_factor_llt(&A, 0, 0);
150 for (
int i=chol->colptr[
j]; i<chol->colptr[
j+1]; ++
i)
151 std::cout << chol->values.d[
i] <<
" ";
156 #ifdef EIGEN_CHOLMOD_SUPPORT 163 A = sm1.asCholmodMatrix();
167 std::vector<int>
perm(cols);
175 c.method [0].ordering = CHOLMOD_NATURAL;
179 L = cholmod_analyze_p(&A, &perm[0], &perm[0], cols, &c);
181 std::cout <<
"cholmod/analyze:\t" << timer.
value() << endl;
184 cholmod_factorize(&A, L, &c);
186 std::cout <<
"cholmod/factorize:\t" << timer.
value() << endl;
188 cholmod_sparse* cholmat = cholmod_factor_to_sparse(L, &c);
190 cholmod_print_factor(L,
"Factors", &c);
192 cholmod_print_sparse(cholmat,
"Chol", &c);
193 cholmod_write_sparse(
stdout, cholmat, 0, 0, &c);
Matrix< Scalar, Dynamic, Dynamic > DenseMatrix
EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const Scalar &x, const OtherScalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
A versatible sparse matrix representation.
double value(int TIMER=CPU_TIMER) const
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
void fillSpdMatrix(float density, int rows, int cols, EigenSparseSelfAdjointMatrix &dst)
SparseMatrix< Scalar, SelfAdjoint|LowerTriangular > EigenSparseSelfAdjointMatrix
void eiToDense(const EigenSparseMatrix &src, DenseMatrix &dst)
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
Array< int, Dynamic, 1 > v
idx_t idx_t idx_t idx_t idx_t * perm
Traits::MatrixL matrixL() const
void doEigen(const char *name, const EigenSparseSelfAdjointMatrix &sm1, int flags=0)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Annotation for function names.
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
int main(int argc, char *argv[])