16 #ifndef EIGEN_SVDBASE_H 17 #define EIGEN_SVDBASE_H 62 template<
typename Derived>
class SVDBase 67 template<
typename Derived_>
76 RowsAtCompileTime = MatrixType::RowsAtCompileTime,
77 ColsAtCompileTime = MatrixType::ColsAtCompileTime,
79 MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,
80 MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,
82 MatrixOptions = MatrixType::Options
89 Derived&
derived() {
return *
static_cast<Derived*
>(
this); }
90 const Derived&
derived()
const {
return *
static_cast<const Derived*
>(
this); }
103 _check_compute_assertions();
104 eigen_assert(computeU() &&
"This SVD decomposition didn't compute U. Did you ask for it?");
119 _check_compute_assertions();
120 eigen_assert(computeV() &&
"This SVD decomposition didn't compute V. Did you ask for it?");
131 _check_compute_assertions();
132 return m_singularValues;
138 _check_compute_assertions();
139 return m_nonzeroSingularValues;
151 _check_compute_assertions();
152 if(m_singularValues.size()==0)
return 0;
154 Index
i = m_nonzeroSingularValues-1;
155 while(i>=0 && m_singularValues.coeff(i) < premultiplied_threshold) --i;
175 m_usePrescribedThreshold =
true;
176 m_prescribedThreshold = threshold;
190 m_usePrescribedThreshold =
false;
200 eigen_assert(m_isInitialized || m_usePrescribedThreshold);
202 Index diagSize = (std::max<Index>)(1,m_diagSize);
203 return m_usePrescribedThreshold ? m_prescribedThreshold
208 inline bool computeU()
const {
return m_computeFullU || m_computeThinU; }
210 inline bool computeV()
const {
return m_computeFullV || m_computeThinV; }
212 inline Index
rows()
const {
return m_rows; }
213 inline Index
cols()
const {
return m_cols; }
215 #ifdef EIGEN_PARSED_BY_DOXYGEN 225 template<
typename Rhs>
238 eigen_assert(m_isInitialized &&
"SVD is not initialized.");
242 #ifndef EIGEN_PARSED_BY_DOXYGEN 243 template<
typename RhsType,
typename DstType>
244 void _solve_impl(
const RhsType &rhs, DstType &dst)
const;
246 template<
bool Conjugate,
typename RhsType,
typename DstType>
247 void _solve_impl_transposed(
const RhsType &rhs, DstType &dst)
const;
258 eigen_assert(m_isInitialized &&
"SVD is not initialized.");
261 template<
bool Transpose_,
typename Rhs>
264 _check_compute_assertions();
265 eigen_assert(computeU() && computeV() &&
"SVDBase::solve(): Both unitaries U and V are required to be computed (thin unitaries suffice).");
266 eigen_assert((Transpose_?
cols():
rows())==b.rows() &&
"SVDBase::solve(): invalid number of rows of the right hand side matrix b");
270 bool allocate(Index
rows, Index
cols,
unsigned int computationOptions) ;
280 Index m_nonzeroSingularValues,
m_rows, m_cols, m_diagSize;
289 m_isInitialized(false),
290 m_isAllocated(false),
291 m_usePrescribedThreshold(false),
292 m_computeFullU(false),
293 m_computeThinU(false),
294 m_computeFullV(false),
295 m_computeThinV(false),
296 m_computationOptions(0),
297 m_rows(-1), m_cols(-1), m_diagSize(0)
299 check_template_parameters();
305 #ifndef EIGEN_PARSED_BY_DOXYGEN 306 template<
typename Derived>
307 template<
typename RhsType,
typename DstType>
314 Index l_rank = rank();
315 tmp.noalias() = m_matrixU.leftCols(l_rank).adjoint() * rhs;
316 tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;
317 dst = m_matrixV.leftCols(l_rank) * tmp;
320 template<
typename Derived>
321 template<
bool Conjugate,
typename RhsType,
typename DstType>
328 Index l_rank = rank();
330 tmp.noalias() = m_matrixV.leftCols(l_rank).transpose().template conjugateIf<Conjugate>() * rhs;
331 tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;
332 dst = m_matrixU.template conjugateIf<!Conjugate>().
leftCols(l_rank) * tmp;
336 template<
typename MatrixType>
344 computationOptions == m_computationOptions)
352 m_isInitialized =
false;
353 m_isAllocated =
true;
354 m_computationOptions = computationOptions;
355 m_computeFullU = (computationOptions &
ComputeFullU) != 0;
356 m_computeThinU = (computationOptions &
ComputeThinU) != 0;
357 m_computeFullV = (computationOptions &
ComputeFullV) != 0;
358 m_computeThinV = (computationOptions &
ComputeThinV) != 0;
359 eigen_assert(!(m_computeFullU && m_computeThinU) &&
"SVDBase: you can't ask for both full and thin U");
360 eigen_assert(!(m_computeFullV && m_computeThinV) &&
"SVDBase: you can't ask for both full and thin V");
362 "SVDBase: thin U and V are only available when your matrix has a dynamic number of columns.");
364 m_diagSize = (
std::min)(m_rows, m_cols);
365 m_singularValues.resize(m_diagSize);
367 m_matrixU.resize(m_rows, m_computeFullU ? m_rows : m_computeThinU ? m_diagSize : 0);
369 m_matrixV.resize(m_cols, m_computeFullV ? m_cols : m_computeThinV ? m_diagSize : 0);
376 #endif // EIGEN_SVDBASE_H
Derived & setThreshold(Default_t)
const Derived & derived() const
unsigned int m_computationOptions
Matrix< Scalar, ColsAtCompileTime, ColsAtCompileTime, MatrixOptions, MaxColsAtCompileTime, MaxColsAtCompileTime > MatrixVType
const MatrixUType & matrixU() const
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
NumTraits< typename MatrixType::Scalar >::Real RealScalar
Eigen::internal::traits< SVDBase >::StorageIndex StorageIndex
Eigen::Index Index
The interface type of indices.
#define EIGEN_IMPLIES(a, b)
#define EIGEN_SIZE_MIN_PREFER_FIXED(a, b)
bool allocate(Index rows, Index cols, unsigned int computationOptions)
bool m_usePrescribedThreshold
Base class of SVD algorithms.
SolverStorage StorageKind
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
SVDBase()
Default Constructor.
Matrix< Scalar, RowsAtCompileTime, RowsAtCompileTime, MatrixOptions, MaxRowsAtCompileTime, MaxRowsAtCompileTime > MatrixUType
SingularValuesType m_singularValues
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const
RealScalar m_prescribedThreshold
Derived & setThreshold(const RealScalar &threshold)
NumTraits< Scalar >::Real RealScalar
RealScalar threshold() const
internal::plain_diag_type< MatrixType, RealScalar >::type SingularValuesType
static void check_template_parameters()
#define EIGEN_DEVICE_FUNC
void _solve_impl(const RhsType &rhs, DstType &dst) const
EIGEN_DEVICE_FUNC ComputationInfo info() const
Reports whether previous computation was successful.
Index nonzeroSingularValues() const
const SingularValuesType & singularValues() const
const MatrixVType & matrixV() const
Pseudo expression representing a solving operation.
Generic expression where a coefficient-wise unary operator is applied to an expression.
#define EIGEN_SIZE_MIN_PREFER_DYNAMIC(a, b)
A base class for matrix decomposition and solvers.
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NColsBlockXpr< internal::get_fixed_value< NColsType >::value >::Type leftCols(NColsType n)
internal::traits< Derived >::MatrixType MatrixType
void _check_compute_assertions() const
Base class for all dense matrices, vectors, and expressions.
MatrixType::Scalar Scalar
void _check_solve_assertion(const Rhs &b) const
#define EIGEN_ONLY_USED_FOR_DEBUG(x)