spqr_support.cpp
Go to the documentation of this file.
1 // This file is part of Eigen, a lightweight C++ template library
2 // for linear algebra.
3 //
4 // Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>
5 //
6 // This Source Code Form is subject to the terms of the Mozilla
7 // Public License v. 2.0. If a copy of the MPL was not distributed
8 
9 #define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS
10 #include "sparse.h"
11 #include <Eigen/SPQRSupport>
12 
13 
14 template<typename MatrixType,typename DenseMat>
15 int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 300)
16 {
17  eigen_assert(maxRows >= maxCols);
18  typedef typename MatrixType::Scalar Scalar;
19  int rows = internal::random<int>(1,maxRows);
20  int cols = internal::random<int>(1,rows);
21  double density = (std::max)(8./(rows*cols), 0.01);
22 
23  A.resize(rows,cols);
24  dA.resize(rows,cols);
25  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);
26  A.makeCompressed();
27  return rows;
28 }
29 
30 template<typename Scalar> void test_spqr_scalar()
31 {
33  MatrixType A;
36  DenseVector refX,x,b;
39 
40  Index m = A.rows();
41  b = DenseVector::Random(m);
42  solver.compute(A);
43  if (solver.info() != Success)
44  {
45  std::cerr << "sparse QR factorization failed\n";
46  exit(0);
47  return;
48  }
49  x = solver.solve(b);
50  if (solver.info() != Success)
51  {
52  std::cerr << "sparse QR factorization failed\n";
53  exit(0);
54  return;
55  }
56  //Compare with a dense solver
57  refX = dA.colPivHouseholderQr().solve(b);
58  VERIFY(x.isApprox(refX,test_precision<Scalar>()));
59 }
60 EIGEN_DECLARE_TEST(spqr_support)
61 {
62  CALL_SUBTEST_1(test_spqr_scalar<double>());
63  CALL_SUBTEST_2(test_spqr_scalar<std::complex<double> >());
64 }
Matrix3f m
SCALAR Scalar
Definition: bench_gemm.cpp:46
#define max(a, b)
Definition: datatypes.h:20
Scalar * b
Definition: benchVecAdd.cpp:17
int generate_sparse_rectangular_problem(MatrixType &A, DenseMat &dA, int maxRows=300, int maxCols=300)
const Solve< SPQR< _MatrixType >, Rhs > solve(const MatrixBase< Rhs > &b) const
MatrixXf MatrixType
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
ComputationInfo info() const
Reports whether previous computation was successful.
Matrix< Scalar, Dynamic, 1 > DenseVector
#define CALL_SUBTEST_1(FUNC)
EIGEN_DECLARE_TEST(spqr_support)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
#define eigen_assert(x)
Definition: Macros.h:1037
void compute(const _MatrixType &matrix)
#define VERIFY(a)
Definition: main.h:380
void test_spqr_scalar()
Sparse QR factorization based on SuiteSparseQR library.
#define CALL_SUBTEST_2(FUNC)
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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:36:19