15 template <
typename MatrixType>
20 Index rank = internal::random<Index>(1, (
std::min)(rows, cols) - 1);
24 MatrixType::RowsAtCompileTime>
42 t.setZero(rows, cols);
43 t.topLeftCorner(rank, rank) =
44 cod.
matrixT().topLeftCorner(rank, rank).template triangularView<Upper>();
49 MatrixType exact_solution = MatrixType::Random(cols, cols2);
63 template <
typename MatrixType,
int Cols2>
66 Rows = MatrixType::RowsAtCompileTime,
67 Cols = MatrixType::ColsAtCompileTime
70 int rank = internal::random<int>(1, (
std::min)(
int(Rows),
int(
Cols)) - 1);
92 template<
typename MatrixType>
void qr()
120 RealScalar threshold =
125 if (x < threshold && y < threshold)
continue;
128 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
130 std::cout <<
"Failure at i=" <<
i <<
", rank=" << rank
131 <<
", threshold=" << threshold << std::endl;
138 m2 = MatrixType::Random(
cols,cols2);
145 m1 = MatrixType::Random(size,size);
149 m3 = m1 * MatrixType::Random(size,cols2);
159 enum { Rows = MatrixType::RowsAtCompileTime,
Cols = MatrixType::ColsAtCompileTime };
162 int rank = internal::random<int>(1, (
std::min)(
int(Rows),
int(
Cols))-1);
183 RealScalar threshold =
188 if (x < threshold && y < threshold)
continue;
191 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
193 std::cout <<
"Failure at i=" <<
i <<
", rank=" << rank
194 <<
", threshold=" << threshold << std::endl;
217 m1.setZero(rows,
cols);
220 RealScalar pow_s_i(1.0);
223 m1.row(
i).tail(rows -
i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows -
i - 1);
226 m1 = (m1 + m1.transpose()).
eval();
230 RealScalar threshold =
235 if (x < threshold && y < threshold)
continue;
238 std::cout <<
"i = " <<
j <<
", |r_ii| = " <<
numext::abs(r(
j,
j)) << std::endl;
240 std::cout <<
"Failure at i=" <<
i <<
", rank=" << qr.
rank()
241 <<
", threshold=" << threshold << std::endl;
254 int size = internal::random<int>(10,50);
257 m1 = MatrixType::Random(size,size);
263 m1 += a * a.adjoint();
267 m3 = MatrixType::Random(size,size);
273 for(
int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();
274 RealScalar absdet =
abs(
m1.diagonal().prod());
302 CALL_SUBTEST_1( qr<MatrixXf>() );
303 CALL_SUBTEST_2( qr<MatrixXd>() );
304 CALL_SUBTEST_3( qr<MatrixXcd>() );
311 CALL_SUBTEST_1( cod<MatrixXf>() );
312 CALL_SUBTEST_2( cod<MatrixXd>() );
313 CALL_SUBTEST_3( cod<MatrixXcd>() );
320 CALL_SUBTEST_1( qr_invertible<MatrixXf>() );
321 CALL_SUBTEST_2( qr_invertible<MatrixXd>() );
322 CALL_SUBTEST_6( qr_invertible<MatrixXcf>() );
323 CALL_SUBTEST_3( qr_invertible<MatrixXcd>() );
326 CALL_SUBTEST_7(qr_verify_assert<Matrix3f>());
327 CALL_SUBTEST_8(qr_verify_assert<Matrix3d>());
328 CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());
329 CALL_SUBTEST_2(qr_verify_assert<MatrixXd>());
330 CALL_SUBTEST_6(qr_verify_assert<MatrixXcf>());
331 CALL_SUBTEST_3(qr_verify_assert<MatrixXcd>());
336 CALL_SUBTEST_1( qr_kahan_matrix<MatrixXf>() );
337 CALL_SUBTEST_2( qr_kahan_matrix<MatrixXd>() );
void test_qr_colpivoting()
const PermutationType & colsPermutation() const
MatrixType matrixZ() const
#define VERIFY_RAISES_ASSERT(a)
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf > svd(m, ComputeThinU|ComputeThinV)
const Solve< CompleteOrthogonalDecomposition, Rhs > solve(const MatrixBase< Rhs > &b) const
const Inverse< ColPivHouseholderQR > inverse() const
const Solve< ColPivHouseholderQR, Rhs > solve(const MatrixBase< Rhs > &b) const
MatrixType::RealScalar logAbsDeterminant() const
bool isInvertible() const
EIGEN_DEVICE_FUNC const LogReturnType log() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Index dimensionOfKernel() const
bool isSurjective() const
const MatrixType & matrixT() const
HouseholderSequenceType householderQ(void) const
Complete orthogonal decomposition (COD) of a matrix.
bool test_isApproxOrLessThan(const Real &a, const Real &b)
#define VERIFY_IS_APPROX(a, b)
ColPivHouseholderQR & compute(const EigenBase< InputType > &matrix)
#define VERIFY_IS_EQUAL(a, b)
const MatrixType & matrixQR() const
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
HouseholderSequenceType householderQ() const
EIGEN_DEVICE_FUNC const Scalar & q
NumTraits< Scalar >::Real RealScalar
const PermutationType & colsPermutation() const
InverseReturnType inverse() const
MatrixType::RealScalar absDeterminant() const
bool isSurjective() const
#define EIGEN_TEST_MAX_SIZE
#define VERIFY_IS_UNITARY(a)
Two-sided Jacobi SVD decomposition of a rectangular matrix.
#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b)
bool isInvertible() const
void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType &m)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
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.
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
Matrix< _Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setRandom(Index size)
const Solve< JacobiSVD< _MatrixType, QRPreconditioner >, Rhs > solve(const MatrixBase< Rhs > &b) const
Index dimensionOfKernel() const
const Inverse< CompleteOrthogonalDecomposition > pseudoInverse() const