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 23 template<
typename SvdType,
typename MatrixType>
30 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
31 ColsAtCompileTime = MatrixType::ColsAtCompileTime
36 typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime> MatrixUType;
37 typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime> MatrixVType;
40 sigma.diagonal() = svd.singularValues().template cast<Scalar>();
41 MatrixUType u = svd.matrixU();
42 MatrixVType
v = svd.matrixV();
43 RealScalar scaling = m.cwiseAbs().maxCoeff();
57 template<
typename SvdType,
typename MatrixType>
59 unsigned int computationOptions,
60 const SvdType& referenceSvd)
66 RealScalar prec = test_precision<RealScalar>();
68 SvdType
svd(m, computationOptions);
74 VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) );
75 VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(),
76 referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint());
81 VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) );
82 VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(),
83 referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint());
98 template<
typename SvdType,
typename MatrixType>
107 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
108 ColsAtCompileTime = MatrixType::ColsAtCompileTime
111 typedef Matrix<Scalar, RowsAtCompileTime, Dynamic> RhsType;
112 typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;
114 RhsType rhs = RhsType::Random(rows, internal::random<Index>(1, cols));
115 SvdType
svd(m, computationOptions);
120 SolutionType
x = svd.solve(rhs);
122 RealScalar residual = (m*x-rhs).norm();
123 RealScalar rhs_norm = rhs.norm();
142 for(
Index k=0;k<x.rows();++k)
148 RealScalar residual_y = (m*y-rhs).norm();
155 residual_y = (m*y-rhs).norm();
165 template<
typename MatrixType>
172 ColsAtCompileTime = MatrixType::ColsAtCompileTime
175 typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;
179 RankAtCompileTime2 = ColsAtCompileTime==
Dynamic ?
Dynamic : (ColsAtCompileTime)/2+1,
180 RowsAtCompileTime3 = ColsAtCompileTime==
Dynamic ?
Dynamic : ColsAtCompileTime+1
182 typedef Matrix<Scalar, RankAtCompileTime2, ColsAtCompileTime> MatrixType2;
183 typedef Matrix<Scalar, RankAtCompileTime2, 1> RhsType2;
184 typedef Matrix<Scalar, ColsAtCompileTime, RankAtCompileTime2> MatrixType2T;
185 Index rank = RankAtCompileTime2==
Dynamic ? internal::random<Index>(1,
cols) :
Index(RankAtCompileTime2);
186 MatrixType2
m2(rank,cols);
190 }
while(
SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision<Scalar>()).rank()!=rank && (++guard)<10);
193 RhsType2 rhs2 = RhsType2::Random(rank);
195 HouseholderQR<MatrixType2T>
qr(m2.adjoint());
196 Matrix<Scalar,Dynamic,1> tmp =
qr.matrixQR().topLeftCorner(rank,rank).template triangularView<Upper>().
adjoint().solve(rhs2);
197 tmp.conservativeResize(cols);
198 tmp.tail(cols-rank).setZero();
199 SolutionType x21 =
qr.householderQ() * tmp;
202 SolutionType x22 = svd2.solve(rhs2);
208 typedef Matrix<Scalar, RowsAtCompileTime3, ColsAtCompileTime> MatrixType3;
209 typedef Matrix<Scalar, RowsAtCompileTime3, 1> RhsType3;
210 Index rows3 = RowsAtCompileTime3==
Dynamic ? internal::random<Index>(rank+1,2*
cols) :
Index(RowsAtCompileTime3);
211 Matrix<Scalar,RowsAtCompileTime3,Dynamic>
C = Matrix<Scalar,RowsAtCompileTime3,Dynamic>::Random(rows3,rank);
212 MatrixType3 m3 = C *
m2;
213 RhsType3 rhs3 = C * rhs2;
215 SolutionType
x3 = svd3.solve(rhs3);
223 template<
typename SvdType,
typename MatrixType>
233 #if defined __INTEL_COMPILER 235 #pragma warning disable 111 244 if (MatrixType::ColsAtCompileTime ==
Dynamic) {
263 VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint());
270 template<
typename Scalar>
277 template<
typename SvdType,
typename MatrixType>
282 Scalar some_inf =
Scalar(1) / zero<Scalar>();
283 VERIFY(
sub(some_inf, some_inf) !=
sub(some_inf, some_inf));
286 Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();
291 m(internal::random<int>(0,9), internal::random<int>(0,9)) = some_inf;
294 m = MatrixType::Zero(10,10);
295 m(internal::random<int>(0,9), internal::random<int>(0,9)) = nan;
318 #if defined __INTEL_COMPILER 321 #pragma warning disable 239 324 M << -7.90884e-313, -4.94e-324,
331 VectorXd value_set(9);
332 value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223;
337 M << value_set(
id(0)), value_set(
id(1)), value_set(
id(2)), value_set(
id(3));
342 if(
id(k)>=value_set.size())
344 while(k<3 &&
id(k)>=value_set.size())
id(++k)++;
345 id.head(k).setZero();
349 }
while((
id<
int(value_set.size())).all());
351 #if defined __INTEL_COMPILER 357 M3 << 4.4331978442502944e+307, -5.8585363752028680e+307, 6.4527017443412964e+307,
358 3.7841695601406358e+307, 2.4331702789740617e+306, -3.5235707140272905e+307,
359 -8.7190887618028355e+307, -7.3453213709232193e+307, -2.4367363684472105e+307;
368 template<
typename MatrixType>
372 VectorXd value_set(3);
373 value_set << 0, 1, -1;
378 M << value_set(
id(0)), value_set(
id(1)), value_set(
id(2)), value_set(
id(3));
383 if(
id(k)>=value_set.size())
385 while(k<3 &&
id(k)>=value_set.size())
id(++k)++;
386 id.head(k).setZero();
390 }
while((
id<
int(value_set.size())).all());
396 Vector3f
v(3.
f, 2.
f, 1.
f);
397 MatrixXf
m = v.asDiagonal();
399 internal::set_is_malloc_allowed(
false);
402 internal::set_is_malloc_allowed(
true);
407 internal::set_is_malloc_allowed(
false);
409 internal::set_is_malloc_allowed(
true);
416 internal::set_is_malloc_allowed(
false);
418 internal::set_is_malloc_allowed(
true);
421 internal::set_is_malloc_allowed(
false);
423 internal::set_is_malloc_allowed(
true);
427 internal::set_is_malloc_allowed(
false);
429 internal::set_is_malloc_allowed(
true);
432 template<
typename SvdType,
typename MatrixType>
440 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
441 ColsAtCompileTime = MatrixType::ColsAtCompileTime
444 typedef Matrix<Scalar, RowsAtCompileTime, 1> RhsType;
456 svd.singularValues();
459 if (ColsAtCompileTime ==
Dynamic)
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)
Q id(Eigen::AngleAxisd(0, Q_z_axis))
EIGEN_DONT_INLINE Scalar zero()
static const double sigma
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
#define SVD_FOR_MIN_NORM(M)
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.
void svd_min_norm(const MatrixType &m, unsigned int computationOptions)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
bool test_isApprox(const Real &a, const Real &b)
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)
bool test_isMuchSmallerThan(const Real &a, const Real &b)
#define CALL_SUBTEST(FUNC)
#define VERIFY_IS_UNITARY(a)
void svd_all_trivial_2x2(void(*cb)(const MatrixType &, bool))
void svd_verify_assert(const MatrixType &m)
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)