16 template <
typename MatrixType>
23 Index rank = internal::random<Index>(1, (
std::min)(rows, cols) - 1);
27 MatrixType::RowsAtCompileTime>
45 t.setZero(rows, cols);
46 t.topLeftCorner(rank, rank) =
47 cod.
matrixT().topLeftCorner(rank, rank).template triangularView<Upper>();
55 MatrixType exact_solution = MatrixType::Random(cols, cols2);
66 template <
typename MatrixType,
int Cols2>
69 Rows = MatrixType::RowsAtCompileTime,
70 Cols = MatrixType::ColsAtCompileTime
74 int rank = internal::random<int>(1, (
std::min)(
int(Rows),
int(
Cols)) - 1);
78 VERIFY(rank == cod.rank());
79 VERIFY(
Cols - cod.rank() == cod.dimensionOfKernel());
80 VERIFY(cod.isInjective() == (rank == Rows));
82 VERIFY(cod.isInvertible() == (cod.isInjective() && cod.isSurjective()));
99 template<
typename MatrixType>
void qr()
129 RealScalar threshold =
134 if (x < threshold && y < threshold)
continue;
137 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
139 std::cout <<
"Failure at i=" <<
i <<
", rank=" << rank
140 <<
", threshold=" << threshold << std::endl;
145 check_solverbase<MatrixType, MatrixType>(
m1,
qr,
rows,
cols, cols2);
151 m1 = MatrixType::Random(size,size);
153 }
while(!qr.isInvertible());
155 m3 = m1 * MatrixType::Random(size,cols2);
165 enum { Rows = MatrixType::RowsAtCompileTime,
Cols = MatrixType::ColsAtCompileTime };
168 int rank = internal::random<int>(1, (
std::min)(
int(Rows),
int(
Cols))-1);
186 RealScalar threshold =
191 if (x < threshold && y < threshold)
continue;
194 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
196 std::cout <<
"Failure at i=" <<
i <<
", rank=" << rank
197 <<
", threshold=" << threshold << std::endl;
220 m1.setZero(rows,
cols);
223 RealScalar pow_s_i(1.0);
226 m1.row(
i).tail(rows -
i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows -
i - 1);
229 m1 = (m1 + m1.transpose()).
eval();
233 RealScalar threshold =
238 if (x < threshold && y < threshold)
continue;
241 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
243 std::cout <<
"Failure at i=" <<
i <<
", rank=" << qr.
rank()
244 <<
", threshold=" << threshold << std::endl;
257 int size = internal::random<int>(10,50);
260 m1 = MatrixType::Random(size,size);
266 m1 += a * a.adjoint();
275 for(
int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();
276 RealScalar absdet =
abs(m1.diagonal().prod());
277 m3 = qr.householderQ();
const Solve< SVDBase< JacobiSVD< _MatrixType, QRPreconditioner > >, Rhs > solve(const MatrixBase< Rhs > &b) const
#define VERIFY_RAISES_ASSERT(a)
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf > svd(m, ComputeThinU|ComputeThinV)
#define CALL_SUBTEST_9(FUNC)
#define CALL_SUBTEST_6(FUNC)
bool isSurjective() const
#define CALL_SUBTEST_4(FUNC)
const MatrixType & matrixT() const
InverseReturnType inverse() const
MatrixType matrixZ() const
#define CALL_SUBTEST_3(FUNC)
#define CALL_SUBTEST_7(FUNC)
#define STATIC_CHECK(COND)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
MatrixType::RealScalar logAbsDeterminant() const
bool isSurjective() const
bool isInvertible() const
Complete orthogonal decomposition (COD) of a matrix.
EIGEN_DEVICE_FUNC const LogReturnType log() const
bool test_isApproxOrLessThan(const Real &a, const Real &b)
const PermutationType & colsPermutation() const
Expression of the inverse of another expression.
HouseholderSequenceType householderQ() const
const MatrixType & matrixQTZ() const
#define VERIFY_IS_APPROX(a, b)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
ConstTransposeReturnType transpose() const
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
Index dimensionOfKernel() const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
#define CALL_SUBTEST_8(FUNC)
EIGEN_DEVICE_FUNC const Scalar & q
HouseholderSequenceType householderQ(void) const
NumTraits< Scalar >::Real RealScalar
bool isInvertible() const
MatrixType::RealScalar absDeterminant() const
MatrixType::RealScalar absDeterminant() const
#define CALL_SUBTEST_5(FUNC)
#define EIGEN_TEST_MAX_SIZE
MatrixType::RealScalar logAbsDeterminant() const
#define VERIFY_IS_UNITARY(a)
Two-sided Jacobi SVD decomposition of a rectangular matrix.
Index dimensionOfKernel() const
#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b)
void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType &m)
#define CALL_SUBTEST_2(FUNC)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Jet< T, N > sqrt(const Jet< T, N > &f)
const Inverse< CompleteOrthogonalDecomposition > pseudoInverse() const
Jet< T, N > pow(const Jet< T, N > &f, double g)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
AdjointReturnType adjoint() 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
const MatrixType & matrixQR() const
const PermutationType & colsPermutation() const
Derived & setRandom(Index size)
const Inverse< ColPivHouseholderQR > inverse() const
EIGEN_DECLARE_TEST(qr_colpivoting)