12 #error a macro SVD_DEFAULT(MatrixType) must be defined prior to including svd_common.h 15 #ifndef SVD_FOR_MIN_NORM 16 #error a macro SVD_FOR_MIN_NORM(MatrixType) must be defined prior to including svd_common.h 24 template<
typename SvdType,
typename MatrixType>
31 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
32 ColsAtCompileTime = MatrixType::ColsAtCompileTime
37 typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime> MatrixUType;
38 typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime> MatrixVType;
41 sigma.diagonal() = svd.singularValues().template cast<Scalar>();
42 MatrixUType u = svd.matrixU();
43 MatrixVType
v = svd.matrixV();
44 RealScalar scaling = m.cwiseAbs().maxCoeff();
58 template<
typename SvdType,
typename MatrixType>
60 unsigned int computationOptions,
61 const SvdType& referenceSvd)
67 RealScalar prec = test_precision<RealScalar>();
69 SvdType
svd(m, computationOptions);
75 VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) );
76 VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(),
77 referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint());
82 VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) );
83 VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(),
84 referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint());
99 template<
typename SvdType,
typename MatrixType>
108 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
109 ColsAtCompileTime = MatrixType::ColsAtCompileTime
112 typedef Matrix<Scalar, RowsAtCompileTime, Dynamic> RhsType;
113 typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;
115 RhsType rhs = RhsType::Random(rows, internal::random<Index>(1, cols));
116 SvdType
svd(m, computationOptions);
121 SolutionType
x = svd.solve(rhs);
123 RealScalar residual = (m*x-rhs).norm();
124 RealScalar rhs_norm = rhs.norm();
143 for(
Index k=0;k<x.rows();++k)
149 RealScalar residual_y = (m*y-rhs).norm();
156 residual_y = (m*y-rhs).norm();
166 template<
typename MatrixType>
173 ColsAtCompileTime = MatrixType::ColsAtCompileTime
176 typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;
180 RankAtCompileTime2 = ColsAtCompileTime==
Dynamic ?
Dynamic : (ColsAtCompileTime)/2+1,
181 RowsAtCompileTime3 = ColsAtCompileTime==
Dynamic ?
Dynamic : ColsAtCompileTime+1
183 typedef Matrix<Scalar, RankAtCompileTime2, ColsAtCompileTime> MatrixType2;
184 typedef Matrix<Scalar, RankAtCompileTime2, 1> RhsType2;
185 typedef Matrix<Scalar, ColsAtCompileTime, RankAtCompileTime2> MatrixType2T;
186 Index rank = RankAtCompileTime2==
Dynamic ? internal::random<Index>(1,
cols) :
Index(RankAtCompileTime2);
187 MatrixType2
m2(rank,cols);
191 }
while(
SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision<Scalar>()).rank()!=rank && (++guard)<10);
194 RhsType2 rhs2 = RhsType2::Random(rank);
196 HouseholderQR<MatrixType2T>
qr(m2.adjoint());
197 Matrix<Scalar,Dynamic,1> tmp =
qr.matrixQR().topLeftCorner(rank,rank).template triangularView<Upper>().
adjoint().solve(rhs2);
198 tmp.conservativeResize(cols);
199 tmp.tail(cols-rank).setZero();
200 SolutionType x21 =
qr.householderQ() * tmp;
203 SolutionType x22 = svd2.solve(rhs2);
209 typedef Matrix<Scalar, RowsAtCompileTime3, ColsAtCompileTime> MatrixType3;
210 typedef Matrix<Scalar, RowsAtCompileTime3, 1> RhsType3;
211 Index rows3 = RowsAtCompileTime3==
Dynamic ? internal::random<Index>(rank+1,2*
cols) :
Index(RowsAtCompileTime3);
212 Matrix<Scalar,RowsAtCompileTime3,Dynamic>
C = Matrix<Scalar,RowsAtCompileTime3,Dynamic>::Random(rows3,rank);
213 MatrixType3 m3 = C *
m2;
214 RhsType3 rhs3 = C * rhs2;
216 SolutionType
x3 = svd3.solve(rhs3);
223 template<
typename MatrixType,
typename SolverType>
230 if(MatrixType::ColsAtCompileTime==
Dynamic)
238 typedef Matrix<typename MatrixType::Scalar, MatrixType::ColsAtCompileTime, MatrixType::ColsAtCompileTime> CMatrixType;
239 check_solverbase<CMatrixType, MatrixType>(
m,
solver,
rows,
cols, cols2);
243 template<
typename SvdType,
typename MatrixType>
255 #if defined __INTEL_COMPILER 257 #pragma warning disable 111 269 if (MatrixType::ColsAtCompileTime ==
Dynamic) {
288 VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint());
295 template<
typename Scalar>
303 template<
typename SvdType,
typename MatrixType>
308 Scalar some_inf =
Scalar(1) / zero<Scalar>();
309 VERIFY(
sub(some_inf, some_inf) !=
sub(some_inf, some_inf));
313 Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();
319 m(internal::random<int>(0,9), internal::random<int>(0,9)) = some_inf;
323 m = MatrixType::Zero(10,10);
324 m(internal::random<int>(0,9), internal::random<int>(0,9)) = nan;
350 #if defined __INTEL_COMPILER 353 #pragma warning disable 239 356 M << -7.90884e-313, -4.94e-324,
363 VectorXd value_set(9);
364 value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223;
369 M << value_set(
id(0)), value_set(
id(1)), value_set(
id(2)), value_set(
id(3));
374 if(
id(k)>=value_set.size())
376 while(k<3 &&
id(k)>=value_set.size())
id(++k)++;
377 id.head(k).setZero();
381 }
while((
id<
int(value_set.size())).all());
383 #if defined __INTEL_COMPILER 389 M3 << 4.4331978442502944e+307, -5.8585363752028680e+307, 6.4527017443412964e+307,
390 3.7841695601406358e+307, 2.4331702789740617e+306, -3.5235707140272905e+307,
391 -8.7190887618028355e+307, -7.3453213709232193e+307, -2.4367363684472105e+307;
400 template<
typename MatrixType>
404 VectorXd value_set(3);
405 value_set << 0, 1, -1;
410 M << value_set(
id(0)), value_set(
id(1)), value_set(
id(2)), value_set(
id(3));
415 if(
id(k)>=value_set.size())
417 while(k<3 &&
id(k)>=value_set.size())
id(++k)++;
418 id.head(k).setZero();
422 }
while((
id<
int(value_set.size())).all());
428 Vector3f
v(3.
f, 2.
f, 1.
f);
429 MatrixXf
m = v.asDiagonal();
431 internal::set_is_malloc_allowed(
false);
434 internal::set_is_malloc_allowed(
true);
439 internal::set_is_malloc_allowed(
false);
441 internal::set_is_malloc_allowed(
true);
448 internal::set_is_malloc_allowed(
false);
450 internal::set_is_malloc_allowed(
true);
453 internal::set_is_malloc_allowed(
false);
455 internal::set_is_malloc_allowed(
true);
459 internal::set_is_malloc_allowed(
false);
461 internal::set_is_malloc_allowed(
true);
464 template<
typename SvdType,
typename MatrixType>
472 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
473 ColsAtCompileTime = MatrixType::ColsAtCompileTime
476 typedef Matrix<Scalar, RowsAtCompileTime, 1> RhsType;
490 svd.singularValues();
502 if (!fullOnly && ColsAtCompileTime ==
Dynamic)
void svd_verify_assert(const MatrixType &m, bool fullOnly=false)
void svd_test_all_computation_options(const MatrixType &m, bool full_only)
#define VERIFY_RAISES_ASSERT(a)
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf > svd(m, ComputeThinU|ComputeThinV)
Matrix< RealScalar, Dynamic, Dynamic > M
void adjoint(const MatrixType &m)
EIGEN_DONT_INLINE Scalar zero()
#define STATIC_CHECK(COND)
BiCGSTAB< SparseMatrix< double > > solver
void svd_test_solvers(const MatrixType &m, const SolverType &solver)
bool test_isMuchSmallerThan(const AnnoyingScalar &a, const AnnoyingScalar &b)
#define SVD_FOR_MIN_NORM(M)
static const Similarity3 id
HouseholderQR< MatrixXf > qr(A)
#define EIGEN_DONT_INLINE
#define VERIFY_IS_APPROX(a, b)
void svd_check_full(const MatrixType &m, const SvdType &svd)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< int, Dynamic, 1 > v
void svd_min_norm(const MatrixType &m, unsigned int computationOptions)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NumTraits< Scalar >::Real RealScalar
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Matrix< Scalar, Dynamic, Dynamic > C
EIGEN_DONT_INLINE T sub(T a, T b)
void svd_compare_to_full(const MatrixType &m, unsigned int computationOptions, const SvdType &referenceSvd)
#define CALL_SUBTEST(FUNC)
#define EIGEN_TEST_MAX_SIZE
bool test_isApprox(const AnnoyingScalar &a, const AnnoyingScalar &b)
#define VERIFY_IS_UNITARY(a)
void svd_all_trivial_2x2(void(*cb)(const MatrixType &, bool))
static const double sigma
Jet< T, N > sqrt(const Jet< T, N > &f)
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 svd_least_square(const MatrixType &m, unsigned int computationOptions)