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);
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);
56 b = dA * DenseVector::Random(A.cols());
68 DenseMat recoveredA = solver.
matrixQ()
69 * DenseMat(solver.
matrixR().template triangularView<Upper>())
75 if (solver.
rank() == A.cols())
80 if(internal::random<float>(0,1)>0.5
f)
84 std::cerr <<
"sparse QR factorization failed\n";
91 std::cerr <<
"sparse QR factorization failed\n";
100 bool rank_deficient = A.cols()>A.rows() || dqr.
rank()<A.cols();
123 if(solver.
rank()==A.cols())
129 MatrixType
Q, QtQ, idM;
132 QtQ = Q * Q.adjoint();
133 idM.resize(Q.rows(), Q.rows()); idM.setIdentity();
134 VERIFY(idM.isApprox(QtQ));
const Solve< ColPivHouseholderQR< _MatrixType >, Rhs > solve(const MatrixBase< Rhs > &b) const
SparseQRMatrixQReturnType< SparseQR > matrixQ() const
ComputationInfo info() const
Reports whether previous computation was successful.
BiCGSTAB< SparseMatrix< double > > solver
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
void test_sparseqr_scalar()
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 QR factorization with numerical column pivoting.
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
NumTraits< Scalar >::Real RealScalar
int generate_sparse_rectangular_problem(MatrixType &A, DenseMat &dA, int maxRows=300, int maxCols=150)
EIGEN_DECLARE_TEST(sparseqr)
bool test_isApprox(const AnnoyingScalar &a, const AnnoyingScalar &b)
InverseReturnType transpose() const
#define CALL_SUBTEST_2(FUNC)
const PermutationType & colsPermutation() 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 setPivotThreshold(const RealScalar &threshold)
const Solve< SparseQR, Rhs > solve(const MatrixBase< Rhs > &B) const
void compute(const MatrixType &mat)