sparseqr.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 // Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>
6 //
7 // This Source Code Form is subject to the terms of the Mozilla
8 // Public License v. 2.0. If a copy of the MPL was not distributed
9 #include "sparse.h"
10 #include <Eigen/SparseQR>
11 
12 template<typename MatrixType,typename DenseMat>
13 int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150)
14 {
15  eigen_assert(maxRows >= maxCols);
16  typedef typename MatrixType::Scalar Scalar;
17  int rows = internal::random<int>(1,maxRows);
18  int cols = internal::random<int>(1,maxCols);
19  double density = (std::max)(8./(rows*cols), 0.01);
20 
21  A.resize(rows,cols);
22  dA.resize(rows,cols);
23  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);
24  A.makeCompressed();
25  int nop = internal::random<int>(0, internal::random<double>(0,1) > 0.5 ? cols/2 : 0);
26  for(int k=0; k<nop; ++k)
27  {
28  int j0 = internal::random<int>(0,cols-1);
29  int j1 = internal::random<int>(0,cols-1);
30  Scalar s = internal::random<Scalar>();
31  A.col(j0) = s * A.col(j1);
32  dA.col(j0) = s * dA.col(j1);
33  }
34 
35 // if(rows<cols) {
36 // A.conservativeResize(cols,cols);
37 // dA.conservativeResize(cols,cols);
38 // dA.bottomRows(cols-rows).setZero();
39 // }
40 
41  return rows;
42 }
43 
44 template<typename Scalar> void test_sparseqr_scalar()
45 {
47  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMat;
49  MatrixType A;
50  DenseMat dA;
51  DenseVector refX,x,b;
54 
55  b = dA * DenseVector::Random(A.cols());
56  solver.compute(A);
57 
58  // Q should be MxM
59  VERIFY_IS_EQUAL(solver.matrixQ().rows(), A.rows());
60  VERIFY_IS_EQUAL(solver.matrixQ().cols(), A.rows());
61 
62  // R should be MxN
63  VERIFY_IS_EQUAL(solver.matrixR().rows(), A.rows());
64  VERIFY_IS_EQUAL(solver.matrixR().cols(), A.cols());
65 
66  // Q and R can be multiplied
67  DenseMat recoveredA = solver.matrixQ()
68  * DenseMat(solver.matrixR().template triangularView<Upper>())
69  * solver.colsPermutation().transpose();
70  VERIFY_IS_EQUAL(recoveredA.rows(), A.rows());
71  VERIFY_IS_EQUAL(recoveredA.cols(), A.cols());
72 
73  // and in the full rank case the original matrix is recovered
74  if (solver.rank() == A.cols())
75  {
76  VERIFY_IS_APPROX(A, recoveredA);
77  }
78 
79  if(internal::random<float>(0,1)>0.5f)
80  solver.factorize(A); // this checks that calling analyzePattern is not needed if the pattern do not change.
81  if (solver.info() != Success)
82  {
83  std::cerr << "sparse QR factorization failed\n";
84  exit(0);
85  return;
86  }
87  x = solver.solve(b);
88  if (solver.info() != Success)
89  {
90  std::cerr << "sparse QR factorization failed\n";
91  exit(0);
92  return;
93  }
94 
95  VERIFY_IS_APPROX(A * x, b);
96 
97  //Compare with a dense QR solver
99  refX = dqr.solve(b);
100 
101  VERIFY_IS_EQUAL(dqr.rank(), solver.rank());
102  if(solver.rank()==A.cols()) // full rank
103  VERIFY_IS_APPROX(x, refX);
104 // else
105 // VERIFY((dA * refX - b).norm() * 2 > (A * x - b).norm() );
106 
107  // Compute explicitly the matrix Q
108  MatrixType Q, QtQ, idM;
109  Q = solver.matrixQ();
110  //Check ||Q' * Q - I ||
111  QtQ = Q * Q.adjoint();
112  idM.resize(Q.rows(), Q.rows()); idM.setIdentity();
113  VERIFY(idM.isApprox(QtQ));
114 
115  // Q to dense
116  DenseMat dQ;
117  dQ = solver.matrixQ();
118  VERIFY_IS_APPROX(Q, dQ);
119 }
121 {
122  for(int i=0; i<g_repeat; ++i)
123  {
124  CALL_SUBTEST_1(test_sparseqr_scalar<double>());
125  CALL_SUBTEST_2(test_sparseqr_scalar<std::complex<double> >());
126  }
127 }
128 
SCALAR Scalar
Definition: bench_gemm.cpp:33
#define max(a, b)
Definition: datatypes.h:20
Quaternion Q
Scalar * b
Definition: benchVecAdd.cpp:17
const Solve< ColPivHouseholderQR, Rhs > solve(const MatrixBase< Rhs > &b) const
Index rank() const
Definition: SparseQR.h:150
MatrixXf MatrixType
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic > A
Definition: bench_gemm.cpp:35
void test_sparseqr_scalar()
Definition: sparseqr.cpp:44
ComputationInfo info() const
Reports whether previous computation was successful.
Definition: SparseQR.h:256
const QRMatrixType & matrixR() const
Definition: SparseQR.h:144
void factorize(const MatrixType &mat)
Performs the numerical QR factorization of the input matrix.
Definition: SparseQR.h:349
Index rows() const
Definition: SparseMatrix.h:136
Matrix< Scalar, Dynamic, 1 > DenseVector
Sparse left-looking rank-revealing QR factorization.
Definition: SparseQR.h:16
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
Definition: main.h:331
Index cols() const
Definition: SparseMatrix.h:138
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
static int g_repeat
Definition: main.h:144
#define eigen_assert(x)
Definition: Macros.h:579
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
RealScalar s
InverseReturnType transpose() const
int generate_sparse_rectangular_problem(MatrixType &A, DenseMat &dA, int maxRows=300, int maxCols=150)
Definition: sparseqr.cpp:13
#define VERIFY(a)
Definition: main.h:325
const PermutationType & colsPermutation() const
Definition: SparseQR.h:180
const Solve< SparseQR, Rhs > solve(const MatrixBase< Rhs > &B) const
Definition: SparseQR.h:234
SparseQRMatrixQReturnType< SparseQR > matrixQ() const
Definition: SparseQR.h:174
void test_sparseqr()
Definition: sparseqr.cpp:120
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
void compute(const MatrixType &mat)
Definition: SparseQR.h:115


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:35