00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #ifndef EIGEN_SUITESPARSEQRSUPPORT_H
00011 #define EIGEN_SUITESPARSEQRSUPPORT_H
00012
00013 namespace Eigen {
00014
00015 template<typename MatrixType> class SPQR;
00016 template<typename SPQRType> struct SPQRMatrixQReturnType;
00017 template<typename SPQRType> struct SPQRMatrixQTransposeReturnType;
00018 template <typename SPQRType, typename Derived> struct SPQR_QProduct;
00019 namespace internal {
00020 template <typename SPQRType> struct traits<SPQRMatrixQReturnType<SPQRType> >
00021 {
00022 typedef typename SPQRType::MatrixType ReturnType;
00023 };
00024 template <typename SPQRType> struct traits<SPQRMatrixQTransposeReturnType<SPQRType> >
00025 {
00026 typedef typename SPQRType::MatrixType ReturnType;
00027 };
00028 template <typename SPQRType, typename Derived> struct traits<SPQR_QProduct<SPQRType, Derived> >
00029 {
00030 typedef typename Derived::PlainObject ReturnType;
00031 };
00032 }
00033
00056 template<typename _MatrixType>
00057 class SPQR
00058 {
00059 public:
00060 typedef typename _MatrixType::Scalar Scalar;
00061 typedef typename _MatrixType::RealScalar RealScalar;
00062 typedef UF_long Index ;
00063 typedef SparseMatrix<Scalar, ColMajor, Index> MatrixType;
00064 typedef PermutationMatrix<Dynamic, Dynamic> PermutationType;
00065 public:
00066 SPQR()
00067 : m_ordering(SPQR_ORDERING_DEFAULT),
00068 m_allow_tol(SPQR_DEFAULT_TOL),
00069 m_tolerance (NumTraits<Scalar>::epsilon())
00070 {
00071 cholmod_l_start(&m_cc);
00072 }
00073
00074 SPQR(const _MatrixType& matrix)
00075 : m_ordering(SPQR_ORDERING_DEFAULT),
00076 m_allow_tol(SPQR_DEFAULT_TOL),
00077 m_tolerance (NumTraits<Scalar>::epsilon())
00078 {
00079 cholmod_l_start(&m_cc);
00080 compute(matrix);
00081 }
00082
00083 ~SPQR()
00084 {
00085
00086 cholmod_l_free_sparse(&m_H, &m_cc);
00087 cholmod_l_free_sparse(&m_cR, &m_cc);
00088 cholmod_l_free_dense(&m_HTau, &m_cc);
00089 std::free(m_E);
00090 std::free(m_HPinv);
00091 cholmod_l_finish(&m_cc);
00092 }
00093 void compute(const _MatrixType& matrix)
00094 {
00095 MatrixType mat(matrix);
00096 cholmod_sparse A;
00097 A = viewAsCholmod(mat);
00098 Index col = matrix.cols();
00099 m_rank = SuiteSparseQR<Scalar>(m_ordering, m_tolerance, col, &A,
00100 &m_cR, &m_E, &m_H, &m_HPinv, &m_HTau, &m_cc);
00101
00102 if (!m_cR)
00103 {
00104 m_info = NumericalIssue;
00105 m_isInitialized = false;
00106 return;
00107 }
00108 m_info = Success;
00109 m_isInitialized = true;
00110 m_isRUpToDate = false;
00111 }
00115 inline Index rows() const {return m_H->nrow; }
00116
00120 inline Index cols() const { return m_cR->ncol; }
00121
00126 template<typename Rhs>
00127 inline const internal::solve_retval<SPQR, Rhs> solve(const MatrixBase<Rhs>& B) const
00128 {
00129 eigen_assert(m_isInitialized && " The QR factorization should be computed first, call compute()");
00130 eigen_assert(this->rows()==B.rows()
00131 && "SPQR::solve(): invalid number of rows of the right hand side matrix B");
00132 return internal::solve_retval<SPQR, Rhs>(*this, B.derived());
00133 }
00134
00135 template<typename Rhs, typename Dest>
00136 void _solve(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const
00137 {
00138 eigen_assert(m_isInitialized && " The QR factorization should be computed first, call compute()");
00139 eigen_assert(b.cols()==1 && "This method is for vectors only");
00140
00141
00142 Dest y;
00143 y = matrixQ().transpose() * b;
00144
00145 Index rk = this->rank();
00146 y.topRows(rk) = this->matrixR().topLeftCorner(rk, rk).template triangularView<Upper>().solve(y.topRows(rk));
00147 y.bottomRows(cols()-rk).setZero();
00148
00149 dest.topRows(cols()) = colsPermutation() * y.topRows(cols());
00150
00151 m_info = Success;
00152 }
00153
00156 const MatrixType matrixR() const
00157 {
00158 eigen_assert(m_isInitialized && " The QR factorization should be computed first, call compute()");
00159 if(!m_isRUpToDate) {
00160 m_R = viewAsEigen<Scalar,ColMajor, typename MatrixType::Index>(*m_cR);
00161 m_isRUpToDate = true;
00162 }
00163 return m_R;
00164 }
00166 SPQRMatrixQReturnType<SPQR> matrixQ() const
00167 {
00168 return SPQRMatrixQReturnType<SPQR>(*this);
00169 }
00171 PermutationType colsPermutation() const
00172 {
00173 eigen_assert(m_isInitialized && "Decomposition is not initialized.");
00174 Index n = m_cR->ncol;
00175 PermutationType colsPerm(n);
00176 for(Index j = 0; j <n; j++) colsPerm.indices()(j) = m_E[j];
00177 return colsPerm;
00178
00179 }
00184 Index rank() const
00185 {
00186 eigen_assert(m_isInitialized && "Decomposition is not initialized.");
00187 return m_cc.SPQR_istat[4];
00188 }
00190 void setSPQROrdering(int ord) { m_ordering = ord;}
00192 void setPivotThreshold(const RealScalar& tol) { m_tolerance = tol; }
00193
00195 cholmod_common *cholmodCommon() const { return &m_cc; }
00196
00197
00203 ComputationInfo info() const
00204 {
00205 eigen_assert(m_isInitialized && "Decomposition is not initialized.");
00206 return m_info;
00207 }
00208 protected:
00209 bool m_isInitialized;
00210 bool m_analysisIsOk;
00211 bool m_factorizationIsOk;
00212 mutable bool m_isRUpToDate;
00213 mutable ComputationInfo m_info;
00214 int m_ordering;
00215 int m_allow_tol;
00216 RealScalar m_tolerance;
00217 mutable cholmod_sparse *m_cR;
00218 mutable MatrixType m_R;
00219 mutable Index *m_E;
00220 mutable cholmod_sparse *m_H;
00221 mutable Index *m_HPinv;
00222 mutable cholmod_dense *m_HTau;
00223 mutable Index m_rank;
00224 mutable cholmod_common m_cc;
00225 template<typename ,typename > friend struct SPQR_QProduct;
00226 };
00227
00228 template <typename SPQRType, typename Derived>
00229 struct SPQR_QProduct : ReturnByValue<SPQR_QProduct<SPQRType,Derived> >
00230 {
00231 typedef typename SPQRType::Scalar Scalar;
00232 typedef typename SPQRType::Index Index;
00233
00234 SPQR_QProduct(const SPQRType& spqr, const Derived& other, bool transpose) : m_spqr(spqr),m_other(other),m_transpose(transpose) {}
00235
00236 inline Index rows() const { return m_transpose ? m_spqr.rows() : m_spqr.cols(); }
00237 inline Index cols() const { return m_other.cols(); }
00238
00239 template<typename ResType>
00240 void evalTo(ResType& res) const
00241 {
00242 cholmod_dense y_cd;
00243 cholmod_dense *x_cd;
00244 int method = m_transpose ? SPQR_QTX : SPQR_QX;
00245 cholmod_common *cc = m_spqr.cholmodCommon();
00246 y_cd = viewAsCholmod(m_other.const_cast_derived());
00247 x_cd = SuiteSparseQR_qmult<Scalar>(method, m_spqr.m_H, m_spqr.m_HTau, m_spqr.m_HPinv, &y_cd, cc);
00248 res = Matrix<Scalar,ResType::RowsAtCompileTime,ResType::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x), x_cd->nrow, x_cd->ncol);
00249 cholmod_l_free_dense(&x_cd, cc);
00250 }
00251 const SPQRType& m_spqr;
00252 const Derived& m_other;
00253 bool m_transpose;
00254
00255 };
00256 template<typename SPQRType>
00257 struct SPQRMatrixQReturnType{
00258
00259 SPQRMatrixQReturnType(const SPQRType& spqr) : m_spqr(spqr) {}
00260 template<typename Derived>
00261 SPQR_QProduct<SPQRType, Derived> operator*(const MatrixBase<Derived>& other)
00262 {
00263 return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(),false);
00264 }
00265 SPQRMatrixQTransposeReturnType<SPQRType> adjoint() const
00266 {
00267 return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);
00268 }
00269
00270 SPQRMatrixQTransposeReturnType<SPQRType> transpose() const
00271 {
00272 return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);
00273 }
00274 const SPQRType& m_spqr;
00275 };
00276
00277 template<typename SPQRType>
00278 struct SPQRMatrixQTransposeReturnType{
00279 SPQRMatrixQTransposeReturnType(const SPQRType& spqr) : m_spqr(spqr) {}
00280 template<typename Derived>
00281 SPQR_QProduct<SPQRType,Derived> operator*(const MatrixBase<Derived>& other)
00282 {
00283 return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(), true);
00284 }
00285 const SPQRType& m_spqr;
00286 };
00287
00288 namespace internal {
00289
00290 template<typename _MatrixType, typename Rhs>
00291 struct solve_retval<SPQR<_MatrixType>, Rhs>
00292 : solve_retval_base<SPQR<_MatrixType>, Rhs>
00293 {
00294 typedef SPQR<_MatrixType> Dec;
00295 EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs)
00296
00297 template<typename Dest> void evalTo(Dest& dst) const
00298 {
00299 dec()._solve(rhs(),dst);
00300 }
00301 };
00302
00303 }
00304
00305 }
00306 #endif