10 #include <Eigen/SparseQR> 12 template<
typename MatrixType,
typename DenseMat>
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);
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)
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);
55 b = dA * DenseVector::Random(A.cols());
67 DenseMat recoveredA = solver.
matrixQ()
68 * DenseMat(solver.
matrixR().template triangularView<Upper>())
74 if (solver.
rank() == A.cols())
79 if(internal::random<float>(0,1)>0.5
f)
83 std::cerr <<
"sparse QR factorization failed\n";
90 std::cerr <<
"sparse QR factorization failed\n";
102 if(solver.
rank()==A.cols())
108 MatrixType
Q, QtQ, idM;
111 QtQ = Q * Q.adjoint();
112 idM.resize(Q.rows(), Q.rows()); idM.setIdentity();
113 VERIFY(idM.isApprox(QtQ));
124 CALL_SUBTEST_1(test_sparseqr_scalar<double>());
const Solve< ColPivHouseholderQR, Rhs > solve(const MatrixBase< Rhs > &b) const
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic > A
void test_sparseqr_scalar()
ComputationInfo info() const
Reports whether previous computation was successful.
const QRMatrixType & matrixR() const
void factorize(const MatrixType &mat)
Performs the numerical QR factorization of the input matrix.
Matrix< Scalar, Dynamic, 1 > DenseVector
Sparse left-looking rank-revealing QR factorization.
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
InverseReturnType transpose() const
int generate_sparse_rectangular_problem(MatrixType &A, DenseMat &dA, int maxRows=300, int maxCols=150)
const PermutationType & colsPermutation() const
const Solve< SparseQR, Rhs > solve(const MatrixBase< Rhs > &B) const
SparseQRMatrixQReturnType< SparseQR > matrixQ() const
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)