diff --git a/.cproject b/.cproject index ef7985e39..ed2d41ca6 100644 --- a/.cproject +++ b/.cproject @@ -5,46 +5,47 @@ - - - - - - - - - - + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -298,573 +299,589 @@ - - -make --j2 -install -true -true -true - - -make --j2 -check -true -true -true - - -make - -clean -true -true -true - - -make --k -check -true -false -true - - -make --j2 -testSimpleCamera.run -true -true -true - - -make --f local.mk -testCal3_S2.run -true -true -true - - -make --j2 -testVSLAMFactor.run -true -true -true - - -make --j2 -testCalibratedCamera.run -true -true -true - - -make --j2 -testGaussianConditional.run -true -true -true - - -make --j2 -testPose2.run -true -true -true - - -make --j2 -testRot3.run -true -true -true - - -make --j2 -testNonlinearOptimizer.run -true -true -true - - -make --j2 -testGaussianFactor.run -true -true -true - - -make --j2 -testGaussianFactorGraph.run -true -true -true - - -make --j2 -testNonlinearFactorGraph.run -true -true -true - - -make --j2 -testPose3.run -true -true -true - - -make --j2 -testVectorMap.run -true -true -true - - -make --j2 -testPoint2.run -true -true -true - - -make --j2 -testNonlinearFactor.run -true -true -true - - -make --j2 -timeGaussianFactor.run -true -true -true - - -make --j2 -timeGaussianFactorGraph.run -true -true -true - - -make --j2 -testGaussianBayesNet.run -true -true -true - - -make -testBayesTree.run -true -false -true - - -make - -testSymbolicBayesNet.run -true -false -true - - -make -testSymbolicFactorGraph.run -true -false -true - - -make --j2 -testVector.run -true -true -true - - -make --j2 -testMatrix.run -true -true -true - - -make --j2 -testVSLAMGraph.run -true -true -true - - -make --j2 -testNonlinearEquality.run -true -true -true - - -make --j2 -testSQP.run -true -true -true - - -make --j2 -testNonlinearConstraint.run -true -true -true - - -make --j2 -testVSLAMConfig.run -true -true -true - - -make --j2 -testOrdering.run -true -true -true - - -make --j2 -testRot2.run -true -true -true - - -make --j2 -testGaussianBayesTree.run -true -true -true - - -make --j2 -testPose3Config.run -true -true -true - - -make --j2 -testUrbanMeasurement.run -true -true -true - - -make --j2 -testUrbanOdometry.run -true -true -true - - -make --j2 -testIterative.run -true -true -true - - -make --j2 -testGaussianISAM2.run -true -true -true - - -make --j2 -testSubgraphPreconditioner.run -true -true -true - - -make --j2 -testBayesNetPreconditioner.run -true -true -true - - -make --j2 -testPose2Factor.run -true -true -true - - -make --j2 -timeRot3.run -true -true -true - - -make --j2 -testPose2SLAM.run -true -true -true - - -make --j2 -testPose2Config.run -true -true -true - - -make --j2 -testLieConfig.run -true -true -true - - -make --j2 -testPlanarSLAM.run -true -true -true - - -make -testGraph.run -true -false -true - - -make --j2 -testPose3SLAM.run -true -true -true - - -make --j2 -testTupleConfig.run -true -true -true - - -make --j2 -testPose2Prior.run -true -true -true - - -make --j2 -testNoiseModel.run -true -true -true - - -make --j2 -testISAM.run -true -true -true - - -make --j2 -testGaussianISAM.run -true -true -true - - -make - -testSimulated2D.run -true -false -true - - -make --j2 -timeMatrix.run -true -true -true - - -make --j2 -testKey.run -true -true -true - - -make --j2 -timeVectorConfig.run -true -true -true - - -make --j2 -testHomography2.run -true -true -true - - -make --j2 -testVectorBTree.run -true -true -true - - -make -testErrors.run -true -false -true - - -make -testDSF.run -true -true -true - - -make --j2 -testFactorGraph.run -true -true -true - - -make -testConstraintOptimizer.run -true -true -true - - -make - -testBTree.run -true -true -true - - -make -testSimulated2DOriented.run -true -false -true - - -make - -testDSFVector.run -true -true -true - - -make --j2 -install -true -true -true - - -make --j2 -clean -true -true -true - - -make --j2 -check -true -true -true - - - - + + + make + -j2 + install + true + true + true + + + make + -j2 + check + true + true + true + + + make + + clean + true + true + true + + + make + -k + check + true + false + true + + + make + -j2 + testSimpleCamera.run + true + true + true + + + make + -f local.mk + testCal3_S2.run + true + true + true + + + make + -j2 + testVSLAMFactor.run + true + true + true + + + make + -j2 + testCalibratedCamera.run + true + true + true + + + make + -j2 + testGaussianConditional.run + true + true + true + + + make + -j2 + testPose2.run + true + true + true + + + make + -j2 + testRot3.run + true + true + true + + + make + -j2 + testNonlinearOptimizer.run + true + true + true + + + make + -j2 + testGaussianFactor.run + true + true + true + + + make + -j2 + testGaussianFactorGraph.run + true + true + true + + + make + -j2 + testNonlinearFactorGraph.run + true + true + true + + + make + -j2 + testPose3.run + true + true + true + + + make + -j2 + testVectorMap.run + true + true + true + + + make + -j2 + testPoint2.run + true + true + true + + + make + -j2 + testNonlinearFactor.run + true + true + true + + + make + -j2 + timeGaussianFactor.run + true + true + true + + + make + -j2 + timeGaussianFactorGraph.run + true + true + true + + + make + -j2 + testGaussianBayesNet.run + true + true + true + + + make + testBayesTree.run + true + false + true + + + make + + testSymbolicBayesNet.run + true + false + true + + + make + testSymbolicFactorGraph.run + true + false + true + + + make + -j2 + testVector.run + true + true + true + + + make + -j2 + testMatrix.run + true + true + true + + + make + -j2 + testVSLAMGraph.run + true + true + true + + + make + -j2 + testNonlinearEquality.run + true + true + true + + + make + -j2 + testSQP.run + true + true + true + + + make + -j2 + testNonlinearConstraint.run + true + true + true + + + make + -j2 + testVSLAMConfig.run + true + true + true + + + make + -j2 + testOrdering.run + true + true + true + + + make + -j2 + testRot2.run + true + true + true + + + make + -j2 + testGaussianBayesTree.run + true + true + true + + + make + -j2 + testPose3Config.run + true + true + true + + + make + -j2 + testUrbanMeasurement.run + true + true + true + + + make + -j2 + testUrbanOdometry.run + true + true + true + + + make + -j2 + testIterative.run + true + true + true + + + make + -j2 + testGaussianISAM2.run + true + true + true + + + make + -j2 + testSubgraphPreconditioner.run + true + true + true + + + make + -j2 + testBayesNetPreconditioner.run + true + true + true + + + make + -j2 + testPose2Factor.run + true + true + true + + + make + -j2 + timeRot3.run + true + true + true + + + make + -j2 + testPose2SLAM.run + true + true + true + + + make + -j2 + testPose2Config.run + true + true + true + + + make + -j2 + testLieConfig.run + true + true + true + + + make + -j2 + testPlanarSLAM.run + true + true + true + + + make + testGraph.run + true + false + true + + + make + -j2 + testPose3SLAM.run + true + true + true + + + make + -j2 + testTupleConfig.run + true + true + true + + + make + -j2 + testPose2Prior.run + true + true + true + + + make + -j2 + testNoiseModel.run + true + true + true + + + make + -j2 + testISAM.run + true + true + true + + + make + -j2 + testGaussianISAM.run + true + true + true + + + make + + testSimulated2D.run + true + false + true + + + make + -j2 + timeMatrix.run + true + true + true + + + make + -j2 + testKey.run + true + true + true + + + make + -j2 + timeVectorConfig.run + true + true + true + + + make + -j2 + testHomography2.run + true + true + true + + + make + -j2 + testVectorBTree.run + true + true + true + + + make + testErrors.run + true + false + true + + + make + testDSF.run + true + true + true + + + make + -j2 + testFactorGraph.run + true + true + true + + + make + testConstraintOptimizer.run + true + true + true + + + make + + testBTree.run + true + true + true + + + make + testSimulated2DOriented.run + true + false + true + + + make + + testDSFVector.run + true + true + true + + + make + + testSPQRUtil.run + true + true + true + + + make + + testInference.run + true + true + true + + + make + -j2 + install + true + true + true + + + make + -j2 + clean + true + true + true + + + make + -j2 + check + true + true + true + + + + - - + + diff --git a/Makefile.am b/Makefile.am index ea66ff12a..cbeb711c3 100644 --- a/Makefile.am +++ b/Makefile.am @@ -3,7 +3,7 @@ ACLOCAL_AMFLAGS = -I m4 # make automake install some standard but missing files AUTOMAKE_OPTIONS = foreign -SUBDIRS = colamd CppUnitLite ldl cpp wrap +SUBDIRS = colamd CppUnitLite ldl spqr_mini cpp wrap # install the matlab toolbox install-exec-hook: @@ -20,6 +20,10 @@ install-exec-hook: cp -f ldl/ldl.h $(prefix)/include/ldl/ && \ cp -f ldl/UFconfig.h $(prefix)/include/ldl/ && \ cp -f ldl/libldl.a $(prefix)/lib/ + install -d $(prefix)/include/spqr_mini && \ + cp -f spqr_mini/*.h $(prefix)/include/spqr_mini/ && \ + cp -f spqr_mini/*.hpp $(prefix)/include/spqr_mini/ && \ + cp -f spqr_mini/libspqr_mini.a $(prefix)/lib/ dist-hook: mkdir $(distdir)/CppUnitLite @@ -36,5 +40,10 @@ dist-hook: cp -p $(srcdir)/ldl/*.h $(distdir)/ldl cp -p $(srcdir)/ldl/*.c $(distdir)/ldl cp -p $(srcdir)/ldl/*.cpp $(distdir)/ldl + mkdir $(distdir)/spqr_mini + cp -p $(srcdir)/spqr_mini/Makefile $(distdir)/spqr_mini + cp -p $(srcdir)/spqr_mini/*.h $(distdir)/spqr_mini + cp -p $(srcdir)/spqr_mini/*.c $(distdir)/spqr_mini + cp -p $(srcdir)/spqr_mini/*.cpp $(distdir)/spqr_mini mkdir $(distdir)/matlab cp -p $(srcdir)/matlab/*.m $(distdir)/matlab diff --git a/configure.ac b/configure.ac index b5a4f5258..585439326 100644 --- a/configure.ac +++ b/configure.ac @@ -4,11 +4,12 @@ AC_PREREQ(2.59) AC_INIT(gtsam, 0.0.0, dellaert@cc.gatech.edu) AM_INIT_AUTOMAKE(gtsam, 0.0.0) -AC_OUTPUT(Makefile cpp/Makefile wrap/Makefile) +AC_OUTPUT(Makefile spqr_mini/Makefile cpp/Makefile wrap/Makefile) AC_CONFIG_MACRO_DIR([m4]) AC_CONFIG_SRCDIR([cpp/cal3_S2.cpp]) AC_CONFIG_HEADER([cpp/config.h]) AC_CONFIG_SRCDIR([wrap/wrap.cpp]) +AC_CONFIG_SRCDIR([spqr_mini/spqr_front.cpp]) # Check for OS AC_CANONICAL_HOST # needs to be called at some point earlier diff --git a/cpp/GaussianConditional.cpp b/cpp/GaussianConditional.cpp index 1f929bc27..d9f639f8e 100644 --- a/cpp/GaussianConditional.cpp +++ b/cpp/GaussianConditional.cpp @@ -63,28 +63,32 @@ bool GaussianConditional::equals(const Conditional &c, double tol) const { // check if the size of the parents_ map is the same if (parents_.size() != p->parents_.size()) return false; - bool equal_R1 = equal_with_abs_tol(R_, p->R_, tol); - bool equal_R2 = equal_with_abs_tol(R_*(-1), p->R_, tol); - bool equal_d1 = ::equal_with_abs_tol(d_, p->d_, tol); - bool equal_d2 = ::equal_with_abs_tol(d_*(-1), p->d_, tol); - // check if R_ and d_ are equal up to a sign - if (!((equal_R1 && equal_d1) || (equal_R2 && equal_d2))) return false; + for (int i=0; iR_, i); + if (!((::equal_with_abs_tol(row1, row2, tol) && fabs(d_(i) - p->d_(i)) < tol) || + (::equal_with_abs_tol(row1, row2*(-1), tol) && fabs(d_(i) + p->d_(i)) < tol))) + return false; + + float sign = ::equal_with_abs_tol(row1, row2, tol) ? 1 : -1; + + // check if the matrices are the same + // iterate over the parents_ map + for (it = parents_.begin(); it != parents_.end(); it++) { + Parents::const_iterator it2 = p->parents_.find(it->first); + if (it2 != p->parents_.end()) { + if (!::equal_with_abs_tol(row_(it->second*sign, i), row_(it2->second,i), tol)) + return false; + } else + return false; + } + + } // check if sigmas are equal if (!(::equal_with_abs_tol(sigmas_, p->sigmas_, tol))) return false; - // check if the matrices are the same - // iterate over the parents_ map - for (it = parents_.begin(); it != parents_.end(); it++) { - Parents::const_iterator it2 = p->parents_.find(it->first); - if (it2 != p->parents_.end()) { - if (!(equal_with_abs_tol(it->second, it2->second, tol)) && - !(equal_with_abs_tol(it->second*(-1), it2->second, tol))) - return false; - } else - return false; - } return true; } diff --git a/cpp/GaussianFactor.cpp b/cpp/GaussianFactor.cpp index f77f93412..b92d45fde 100644 --- a/cpp/GaussianFactor.cpp +++ b/cpp/GaussianFactor.cpp @@ -166,16 +166,29 @@ bool GaussianFactor::equals(const Factor& f, double tol) const { const_iterator it1 = As_.begin(), it2 = lf->As_.begin(); if(As_.size() != lf->As_.size()) return false; - for(; it1 != As_.end(); it1++, it2++) { - const Symbol& j1 = it1->first, j2 = it2->first; - const Matrix A1 = it1->second, A2 = it2->second; - if (j1 != j2) return false; - if (!equal_with_abs_tol(A1,A2,tol)) - return false; - } + // check whether each row is up to a sign + for (int i=0; i row1; + list row2; + row1.push_back(Vector_(1, b_(i))); + row2.push_back(Vector_(1, lf->b_(i))); - if( !(::equal_with_abs_tol(b_, (lf->b_),tol)) ) - return false; + for(; it1 != As_.end(); it1++, it2++) { + const Symbol& j1 = it1->first, j2 = it2->first; + const Matrix A1 = it1->second, A2 = it2->second; + if (j1 != j2) return false; + + row1.push_back(row_(A1,i)); + row2.push_back(row_(A2,i)); + } + + Vector r1 = concatVectors(row1); + Vector r2 = concatVectors(row2); + if( !::equal_with_abs_tol(r1, r2, tol) && + !::equal_with_abs_tol(r1*(-1), r2, tol)) { + return false; + } + } return model_->equals(*(lf->model_),tol); } diff --git a/cpp/GaussianFactorGraph.cpp b/cpp/GaussianFactorGraph.cpp index fb65ac5d3..db5868070 100644 --- a/cpp/GaussianFactorGraph.cpp +++ b/cpp/GaussianFactorGraph.cpp @@ -203,7 +203,8 @@ VectorConfig GaussianFactorGraph::optimize(const Ordering& ordering, bool old) GaussianBayesNet chordalBayesNet = eliminate(ordering, old); // calculate new configuration (using backsubstitution) - return ::optimize(chordalBayesNet); + VectorConfig delta = ::optimize(chordalBayesNet); + return delta; } /* ************************************************************************* */ diff --git a/cpp/Makefile.am b/cpp/Makefile.am index c2383cf19..d051c644e 100644 --- a/cpp/Makefile.am +++ b/cpp/Makefile.am @@ -29,12 +29,14 @@ version = $(current):$(revision):$(age) # we specify the library in levels # basic Math -sources = Vector.cpp svdcmp.cpp Matrix.cpp -check_PROGRAMS = testVector testMatrix +sources = Vector.cpp svdcmp.cpp Matrix.cpp SPQRUtil.cpp +check_PROGRAMS = testVector testMatrix testSPQRUtil testVector_SOURCES = testVector.cpp testVector_LDADD = libgtsam.la testMatrix_SOURCES = testMatrix.cpp testMatrix_LDADD = libgtsam.la +testSPQRUtil_SOURCES = testSPQRUtil.cpp +testSPQRUtil_LDADD = libgtsam.la # GTSAM basics # The header files will be installed in ~/include/gtsam @@ -291,7 +293,7 @@ AM_CXXFLAGS = -I$(boost) -fPIC lib_LTLIBRARIES = libgtsam.la libgtsam_la_SOURCES = $(sources) libgtsam_la_CPPFLAGS = $(AM_CXXFLAGS) -libgtsam_la_LDFLAGS = -version-info $(version) -L../colamd -lcolamd -L../ldl -lldl # ../ldl/libldl.a -lboost_serialization-mt +libgtsam_la_LDFLAGS = -version-info $(version) -L../colamd -lcolamd -L../ldl -lldl -L../spqr_mini -lspqr_mini # ../ldl/libldl.a -lboost_serialization-mt # enable debug if --enable-debug is set in configure if DEBUG @@ -304,13 +306,6 @@ include_HEADERS = $(headers) AM_CXXFLAGS += -I.. AM_LDFLAGS = -L../CppUnitLite -lCppUnitLite $(BOOST_LDFLAGS) $(boost_serialization) -# adding SparseQR support -if USE_SPQR -AM_CXXFLAGS += -I$(HOME)/include/SuiteSparse -DUSE_SPQR -AM_LDFLAGS += -L$(HOME)/lib/SuiteSparse -lufconfig -lamd -lcamd -lcolamd -lbtf -lklu -lldl -lccolamd -lumfpack -lcholmod -lcxsparse -lspqr -#AM_LDFLAGS += -L$(HOME)/lib/SuiteSparse -lsqpr -endif - # adding cblas implementation - split into a default linux version using the # autotools script, and a mac version that is hardcoded # NOTE: the GT_USE_CBLAS is just used as a means of detecting when blas is available diff --git a/cpp/Matrix.cpp b/cpp/Matrix.cpp index 0d0ca56e2..6375a925b 100644 --- a/cpp/Matrix.cpp +++ b/cpp/Matrix.cpp @@ -155,6 +155,20 @@ bool assert_equal(const std::list& As, const std::list& Bs, doub return true; } +/* ************************************************************************* */ +bool linear_dependent(const Matrix& A, const Matrix& B, double tol) { + size_t n1 = A.size2(), m1 = A.size1(); + size_t n2 = B.size2(), m2 = B.size1(); + + if(m1!=m2 || n1!=n2) return false; + + for(int i=0; i& As, const std::list& Bs, double tol = 1e-9); +/** + * check whether the rows of two matrices are linear indepdent + */ +bool linear_dependent(const Matrix& A, const Matrix& B, double tol = 1e-9); + /** * overload * for matrix-vector multiplication (as BOOST does not) */ diff --git a/cpp/NoiseModel.cpp b/cpp/NoiseModel.cpp index 46cdd17d3..a0689ab29 100644 --- a/cpp/NoiseModel.cpp +++ b/cpp/NoiseModel.cpp @@ -20,6 +20,7 @@ #include "NoiseModel.h" #include "SharedDiagonal.h" +#include "SPQRUtil.h" namespace ublas = boost::numeric::ublas; typedef ublas::matrix_column column; @@ -104,8 +105,6 @@ void Gaussian::WhitenInPlace(Matrix& H) const { // General QR, see also special version in Constrained SharedDiagonal Gaussian::QR(Matrix& Ab) const { - bool verbose = false; - if (verbose) cout << "\nIn Gaussian::QR" << endl; // get size(A) and maxRank // TODO: really no rank problems ? @@ -113,19 +112,23 @@ SharedDiagonal Gaussian::QR(Matrix& Ab) const { size_t maxRank = min(m,n); // pre-whiten everything (cheaply if possible) - if (verbose) gtsam::print(Ab, "Ab before whitening"); WhitenInPlace(Ab); - if (verbose) gtsam::print(Ab, "Ab after whitening"); // Perform in-place Householder #ifdef GT_USE_LAPACK - householder(Ab); + long* Stair = MakeStairs(Ab); +// double t0, t1; +// t0 = clock(); +// gtsam::print(Ab, "Ab"); + householder_spqr(Ab, Stair); +// householder_spqr(Ab); +// gtsam::print(Ab, "Ab"); +// t1 = clock(); +// printf("QR: %ld %ld %g\n", m, n, (double) (t1 - t0) / CLOCKS_PER_SEC * 1000); #else householder(Ab, maxRank); #endif - if (verbose) gtsam::print(Ab, "Ab before householder"); - return Unit::Create(maxRank); } diff --git a/cpp/SPQRUtil.cpp b/cpp/SPQRUtil.cpp new file mode 100644 index 000000000..06f3b2720 --- /dev/null +++ b/cpp/SPQRUtil.cpp @@ -0,0 +1,142 @@ +/* + * SPQRUtil.cpp + * + * Created on: Jul 1, 2010 + * Author: nikai + * Description: the utility functions for SPQR + */ + +#include +#include "SPQRUtil.h" + +using namespace std; + +#ifdef GT_USE_LAPACK +namespace gtsam { + + /* ************************************************************************* */ + long* MakeStairs(Matrix& A) { + + const long m = A.size1(); + const long n = A.size2(); + + // record the starting pointer of each row + double* a[m]; + a[0] = A.data().begin(); + for(int i=1; i i_zeros, i_nonzeros, i_all; + map i2vi; + for(int i = i0; i < m; i++) { + i_all.push_back(i); + i2vi.insert(make_pair(i, i-i0)); + if (*(a[i]) == 0) + i_zeros.push_back(i); + else + i_nonzeros.push_back(i); + } + + // resort the rows from i_all to i_target + vector& i_target = i_nonzeros; + i_target.insert(i_nonzeros.end(), i_zeros.begin(), i_zeros.end()); + sizeOfRow = (n - j) * sizeof(double); + for (int vi=0; vi(m, n, npiv, tol, ntol, fchunk, + a, Stair, Rdead, Tau, W, &wscale, &wssq, &cc); + + long k0 = 0; + long j0; + memset(A.data().begin(), 0, m*n*sizeof(double)); + for(long j=0; j + +namespace gtsam { + + /** make stairs and speed up householder_spqr. Stair is defined as the row index of where zero entries start in each column */ + long* MakeStairs(Matrix &A); + + /** Householder tranformation, zeros below diagonal */ + void householder_spqr(Matrix &A, long* Stair = NULL); + +} +#endif diff --git a/cpp/Vector.cpp b/cpp/Vector.cpp index f6975aefc..c5e072151 100644 --- a/cpp/Vector.cpp +++ b/cpp/Vector.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include #ifdef WIN32 @@ -201,6 +202,25 @@ namespace gtsam { return false; } + /* ************************************************************************* */ + bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol) { + if (vec1.size()!=vec2.size()) return false; + Vector::const_iterator it1 = vec1.begin(); + Vector::const_iterator it2 = vec2.begin(); + boost::optional scale; + for(size_t i=0; itol&&fabs(it2[i])tol)) + return false; + if(it1[i] == 0 && it2[i] == 0) + continue; + if (!scale) + scale = it1[i] / it2[i]; + else if (fabs(it1[i] - it2[i] * (*scale)) > tol) + return false; + } + return scale.is_initialized(); + } + /* ************************************************************************* */ Vector sub(const Vector &v, size_t i1, size_t i2) { size_t n = i2-i1; diff --git a/cpp/Vector.h b/cpp/Vector.h index 23b354a98..d02c4d182 100644 --- a/cpp/Vector.h +++ b/cpp/Vector.h @@ -148,6 +148,15 @@ bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9); bool assert_equal(SubVector vec1, SubVector vec2, double tol=1e-9); bool assert_equal(ConstSubVector vec1, ConstSubVector vec2, double tol=1e-9); +/** + * check whether two vectors are linearly dependent + * @param vec1 Vector + * @param vec2 Vector + * @param tol 1e-9 + * @return bool + */ +bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9); + /** * extract subvector, slice semantics, i.e. range = [i1,i2[ excluding i2 * @param v Vector diff --git a/cpp/testMatrix.cpp b/cpp/testMatrix.cpp index fce3d0bf2..5c09bdaf4 100644 --- a/cpp/testMatrix.cpp +++ b/cpp/testMatrix.cpp @@ -993,6 +993,30 @@ TEST( matrix, LDL_factorization ) { } +/* ************************************************************************* */ +TEST( matrix, linear_dependent ) +{ + Matrix A = Matrix_(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0); + Matrix B = Matrix_(2, 3, -1.0, -2.0, -3.0, 8.0, 10.0, 12.0); + CHECK(linear_dependent(A, B)); +} + +/* ************************************************************************* */ +TEST( matrix, linear_dependent2 ) +{ + Matrix A = Matrix_(2, 3, 0.0, 2.0, 3.0, 4.0, 5.0, 6.0); + Matrix B = Matrix_(2, 3, 0.0, -2.0, -3.0, 8.0, 10.0, 12.0); + CHECK(linear_dependent(A, B)); +} + +/* ************************************************************************* */ +TEST( matrix, linear_dependent3 ) +{ + Matrix A = Matrix_(2, 3, 0.0, 2.0, 3.0, 4.0, 5.0, 6.0); + Matrix B = Matrix_(2, 3, 0.0, -2.0, -3.0, 8.1, 10.0, 12.0); + CHECK(!linear_dependent(A, B)); +} + /* ************************************************************************* */ int main() { TestResult tr; diff --git a/cpp/testNoiseModel.cpp b/cpp/testNoiseModel.cpp index 2f4e6ec76..debb58ef1 100644 --- a/cpp/testNoiseModel.cpp +++ b/cpp/testNoiseModel.cpp @@ -160,7 +160,7 @@ TEST( NoiseModel, QR ) 0.0, 11.1803, 0.0, -2.23607, 0.0, -8.94427,-1.56525, 0.0, 0.0, 4.47214, 0.0, -4.47214, 0.0, 0.0, 0.0, 0.0, 0.0, 4.47214, 0.0, -4.47214, 0.894427); - CHECK(assert_equal(expectedRd1,Ab1,1e-4)); // Ab was modified in place !!! + CHECK(linear_dependent(expectedRd1,Ab1,1e-4)); // Ab was modified in place !!! // Call Constrained version SharedDiagonal constrained = noiseModel::Constrained::MixedSigmas(sigmas); @@ -172,7 +172,7 @@ TEST( NoiseModel, QR ) 0., 1., 0.,-0.2, 0., -0.8,-0.14, 0., 0., 1., 0., -1., 0., 0.0, 0., 0., 0., 1., 0., -1., 0.2); - CHECK(assert_equal(expectedRd2,Ab2,1e-6)); // Ab was modified in place !!! + CHECK(linear_dependent(expectedRd2,Ab2,1e-6)); // Ab was modified in place !!! } /* ************************************************************************* */ diff --git a/cpp/testPose2SLAM.cpp b/cpp/testPose2SLAM.cpp index 3aab814cc..9ccbbae6d 100644 --- a/cpp/testPose2SLAM.cpp +++ b/cpp/testPose2SLAM.cpp @@ -115,6 +115,44 @@ TEST(Pose2Graph, optimize) { CHECK(assert_equal(expected, *optimizer.config())); } +/* ************************************************************************* */ +// test optimization with 3 poses +TEST(Pose2Graph, optimizeThreePoses) { + + // Create a hexagon of poses + Pose2Config hexagon = pose2SLAM::circle(3,1.0); + Pose2 p0 = hexagon[0], p1 = hexagon[1]; + + // create a Pose graph with one equality constraint and one measurement + shared_ptr fg(new Pose2Graph); + fg->addHardConstraint(0, p0); + Pose2 delta = between(p0,p1); + fg->addConstraint(0, 1, delta, covariance); + fg->addConstraint(1, 2, delta, covariance); + fg->addConstraint(2, 0, delta, covariance); + + // Create initial config + boost::shared_ptr initial(new Pose2Config()); + initial->insert(0, p0); + initial->insert(1, expmap(hexagon[1],Vector_(3,-0.1, 0.1,-0.1))); + initial->insert(2, expmap(hexagon[2],Vector_(3, 0.1,-0.1, 0.1))); + + // Choose an ordering + shared_ptr ordering(new Ordering); + *ordering += "x0","x1","x2"; + + // optimize + pose2SLAM::Optimizer::shared_solver solver(new pose2SLAM::Optimizer::solver(ordering)); + pose2SLAM::Optimizer optimizer0(fg, initial, solver); + pose2SLAM::Optimizer::verbosityLevel verbosity = pose2SLAM::Optimizer::SILENT; + pose2SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt(1e-15, 1e-15, verbosity); + + Pose2Config actual = *optimizer.config(); + + // Check with ground truth + CHECK(assert_equal(hexagon, actual)); +} + /* ************************************************************************* */ // test optimization with 6 poses arranged in a hexagon and a loop closure TEST(Pose2Graph, optimizeCircle) { diff --git a/cpp/testSPQRUtil.cpp b/cpp/testSPQRUtil.cpp new file mode 100644 index 000000000..7d4da7239 --- /dev/null +++ b/cpp/testSPQRUtil.cpp @@ -0,0 +1,128 @@ +/** + * @file testSPQRUtil.cpp + * @brief Unit test for SPQR utility functions + * @author Kai Ni + **/ + +#include +#include +#include "SPQRUtil.h" + +using namespace std; +using namespace gtsam; + +#ifdef GT_USE_LAPACK +/* ************************************************************************* */ +TEST(SPQRUtil, MakeStair) +{ + double data[] = { -5, 0, 5, 0, 0, 0, -1, + 00,-5, 0, 5, 0, 0, 1.5, + 10, 0, 0, 0,-10,0, 2, + 00, 10,0, 0, 0, -10, -1 }; + Matrix A = Matrix_(4, 7, data); + + long* Stair = MakeStairs(A); + + double data2[] = { -5, 0, 5, 0, 0, 0, -1, + 10, 0, 0, 0,-10,0, 2, + 00,-5, 0, 5, 0, 0, 1.5, + 00, 10,0, 0, 0, -10, -1 }; + Matrix A_expected = Matrix_(4, 7, data2); + CHECK(assert_equal(A_expected, A, 1e-10)); + + long Stair_expected[] = {2, 4, 4, 4, 4, 4, 4}; + for (int i=0; i<7; i++) + DOUBLES_EQUAL(Stair_expected[i], Stair[i], 1e-7); + delete []Stair; +} + +/* ************************************************************************* */ +TEST(SPQRUtil, MakeStair2) +{ + double data[] = { 0.1, 0, 0, 0, + 0, 0.3, 0, 0, + 0, 0, 0.3, 0, + 1.6,-0.2, -2.5, 0.2, + 0, 1.6, 0.7, 0.1, + 0, 0, -7.8, 0.7 }; + Matrix A = Matrix_(6, 4, data); + + long* Stair = MakeStairs(A); + + double data2[] = { 0.1, 0, 0, 0, + 1.6,-0.2, -2.5, 0.2, + 0, 0.3, 0, 0, + 0, 1.6, 0.7, 0.1, + 0, 0, 0.3, 0, + 0, 0, -7.8, 0.7 + }; + Matrix A_expected = Matrix_(6, 4, data2); + CHECK(assert_equal(A_expected, A, 1e-10)); + + long Stair_expected[] = {2, 4, 6, 6}; + for (int i=0; i<4; i++) + DOUBLES_EQUAL(Stair_expected[i], Stair[i], 1e-7); + delete []Stair; +} + +/* ************************************************************************* */ +TEST(SPQRUtil, houseHolder_spqr) +{ + double data[] = { -5, 0, 5, 0, 0, 0, -1, + 00,-5, 0, 5, 0, 0, 1.5, + 10, 0, 0, 0,-10,0, 2, + 00, 10,0, 0, 0, -10, -1 }; + + // check in-place householder, with v vectors below diagonal + double data1[] = { 11.1803, 0, -2.2361, 0, -8.9443, 0, 2.236, + 0, 11.1803, 0, -2.2361, 0, -8.9443, -1.565, + 0, 0, 4.4721, 0, -4.4721, 0, 0, + 0, 0, 0, 4.4721, 0, -4.4721, 0.894 }; + Matrix expected1 = Matrix_(4, 7, data1); + Matrix A1 = Matrix_(4, 7, data); + householder_spqr(A1); + CHECK(assert_equal(expected1, A1, 1e-3)); +} + +/* ************************************************************************* */ +TEST(SPQRUtil, houseHolder_spqr2) +{ + double data[] = { -5, 0, 5, 0, 0, 0, -1, + 00,-5, 0, 5, 0, 0, 1.5, + 10, 0, 0, 0,-10,0, 2, + 00, 10,0, 0, 0, -10, -1 }; + + // check in-place householder, with v vectors below diagonal + double data1[] = { 11.1803, 0, -2.2361, 0, -8.9443, 0, 2.236, + 0, -11.1803, 0, 2.2361, 0, 8.9443, 1.565, + 0, 0, -4.4721, 0, 4.4721, 0, 0, + 0, 0, 0, 4.4721, 0, -4.4721, 0.894 }; + Matrix expected1 = Matrix_(4, 7, data1); + Matrix A1 = Matrix_(4, 7, data); + long* Stair = MakeStairs(A1); + householder_spqr(A1, Stair); + CHECK(assert_equal(expected1, A1, 1e-3)); +} + +/* ************************************************************************* */ +TEST(SPQRUtil, houseHolder_spqr3) +{ + double data[] = { 1, 1, 9, + 1, 0, 5}; + + // check in-place householder, with v vectors below diagonal + double data1[] = {-sqrt(2), -1/sqrt(2), -7*sqrt(2), + 0, -1/sqrt(2), -4/sqrt(2)}; + Matrix expected1 = Matrix_(2, 3, data1); + Matrix A1 = Matrix_(2, 3, data); + householder_spqr(A1); + CHECK(assert_equal(expected1, A1, 1e-3)); +} +#endif + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/cpp/testVector.cpp b/cpp/testVector.cpp index 710063fbd..7cfd8f319 100644 --- a/cpp/testVector.cpp +++ b/cpp/testVector.cpp @@ -265,6 +265,30 @@ TEST( TestVector, reciprocal ) CHECK(assert_equal(Vector_(3, 1.0, 0.5, 0.25),reciprocal(v))); } +/* ************************************************************************* */ +TEST( TestVector, linear_dependent ) +{ + Vector v1 = Vector_(3, 1.0, 2.0, 3.0); + Vector v2 = Vector_(3, -2.0, -4.0, -6.0); + CHECK(linear_dependent(v1, v2)); +} + +/* ************************************************************************* */ +TEST( TestVector, linear_dependent2 ) +{ + Vector v1 = Vector_(3, 0.0, 2.0, 0.0); + Vector v2 = Vector_(3, 0.0, -4.0, 0.0); + CHECK(linear_dependent(v1, v2)); +} + +/* ************************************************************************* */ +TEST( TestVector, linear_dependent3 ) +{ + Vector v1 = Vector_(3, 0.0, 2.0, 0.0); + Vector v2 = Vector_(3, 0.1, -4.1, 0.0); + CHECK(!linear_dependent(v1, v2)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ diff --git a/spqr_mini/Makefile.am b/spqr_mini/Makefile.am new file mode 100644 index 000000000..9a63ff241 --- /dev/null +++ b/spqr_mini/Makefile.am @@ -0,0 +1,29 @@ +# the install destination +includedir = ${prefix}/include/spqr_mini +libdir = ${exec_prefix}/lib + +if USE_LAPACK_MACOS + sources = cholmod_common.c cholmod_memory.c spqr_front.cpp spqr_larftb.cpp + headers = UFconfig.h cholmod_common.h cholmod_internal.h cholmod_blas.h cholmod_core.h + headers += SuiteSparseQR_definitions.h SuiteSparseQR_subset.hpp spqr_subset.hpp spqr_larftb.h spqr_front.h + + AM_CXXFLAGS = -fPIC + + # create both dynamic and static libraries + lib_LTLIBRARIES = libspqr_mini.la + libspqr_mini_la_SOURCES = $(sources) + + include_HEADERS = $(headers) + + AM_CXXFLAGS += -DGT_USE_LAPACK -DDLONG + +if USE_VECLIB_MACOS +AM_CXXFLAGS += -DYA_BLAS -DYA_LAPACK -DYA_BLASMULT -I/System/Library/Frameworks/vecLib.framework/Headers +libspqr_mini_la_CPPFLAGS = -DDLONG -DGT_USE_CBLAS -DYA_BLAS -DYA_LAPACK -DYA_BLASMULT -I/System/Library/Frameworks/vecLib.framework/Headers +AM_LDFLAGS = -lcblas -latlas +libspqr_mini_la_LDFLAGS = -framework vecLib -lcblas -latlas +endif + +endif + + diff --git a/spqr_mini/SuiteSparseQR_definitions.h b/spqr_mini/SuiteSparseQR_definitions.h new file mode 100644 index 000000000..0e903cdb4 --- /dev/null +++ b/spqr_mini/SuiteSparseQR_definitions.h @@ -0,0 +1,69 @@ +/* ========================================================================== */ +/* === SuiteSparseQR_definitions.h ========================================== */ +/* ========================================================================== */ + +/* Core definitions for both C and C++ programs. */ + +#ifndef SUITESPARSEQR_DEFINITIONS_H +#define SUITESPARSEQR_DEFINITIONS_H + +/* ordering options */ +#define SPQR_ORDERING_FIXED 0 +#define SPQR_ORDERING_NATURAL 1 +#define SPQR_ORDERING_COLAMD 2 +#define SPQR_ORDERING_GIVEN 3 /* only used for C/C++ interface */ +#define SPQR_ORDERING_CHOLMOD 4 /* CHOLMOD best-effort (COLAMD, METIS,...)*/ +#define SPQR_ORDERING_AMD 5 /* AMD(A'*A) */ +#define SPQR_ORDERING_METIS 6 /* metis(A'*A) */ +#define SPQR_ORDERING_DEFAULT 7 /* SuiteSparseQR default ordering */ +#define SPQR_ORDERING_BEST 8 /* try COLAMD, AMD, and METIS; pick best */ +#define SPQR_ORDERING_BESTAMD 9 /* try COLAMD and AMD; pick best */ + +/* Let [m n] = size of the matrix after pruning singletons. The default + * ordering strategy is to use COLAMD if m <= 2*n. Otherwise, AMD(A'A) is + * tried. If there is a high fill-in with AMD then try METIS(A'A) and take + * the best of AMD and METIS. METIS is not tried if it isn't installed. */ + +/* tol options */ +#define SPQR_DEFAULT_TOL (-2) /* if tol <= -2, the default tol is used */ +#define SPQR_NO_TOL (-1) /* if -2 < tol < 0, then no tol is used */ + +/* for qmult, method can be 0,1,2,3: */ +#define SPQR_QTX 0 +#define SPQR_QX 1 +#define SPQR_XQT 2 +#define SPQR_XQ 3 + +/* system can be 0,1,2,3: Given Q*R=A*E from SuiteSparseQR_factorize: */ +#define SPQR_RX_EQUALS_B 0 /* solve R*X=B or X = R\B */ +#define SPQR_RETX_EQUALS_B 1 /* solve R*E'*X=B or X = E*(R\B) */ +#define SPQR_RTX_EQUALS_B 2 /* solve R'*X=B or X = R'\B */ +#define SPQR_RTX_EQUALS_ETB 3 /* solve R'*X=E'*B or X = R'\(E'*B) */ + +/* ========================================================================== */ +/* === SuiteSparseQR version ================================================ */ +/* ========================================================================== */ + +/* + All versions of SuiteSparseQR will include the following definitions. + As an example, to test if the version you are using is 1.3 or later: + + if (SPQR_VERSION >= SPQR_VER_CODE (1,3)) ... + + This also works during compile-time: + + #if SPQR_VERSION >= SPQR_VER_CODE (1,3) + printf ("This is version 1.3 or later\n") ; + #else + printf ("This is version is earlier than 1.3\n") ; + #endif + */ + +#define SPQR_DATE "Nov 30, 2009" +#define SPQR_VER_CODE(main,sub) ((main) * 1000 + (sub)) +#define SPQR_MAIN_VERSION 1 +#define SPQR_SUB_VERSION 2 +#define SPQR_SUBSUB_VERSION 0 +#define SPQR_VERSION SPQR_VER_CODE(SPQR_MAIN_VERSION,SPQR_SUB_VERSION) + +#endif diff --git a/spqr_mini/SuiteSparseQR_subset.hpp b/spqr_mini/SuiteSparseQR_subset.hpp new file mode 100644 index 000000000..5bb99a00e --- /dev/null +++ b/spqr_mini/SuiteSparseQR_subset.hpp @@ -0,0 +1,604 @@ +// ============================================================================= +// === SuiteSparseQR.hpp ======================================================= +// ============================================================================= + +// User include file for C++ programs. + +#ifndef SUITESPARSEQR_H +#define SUITESPARSEQR_H + +// ----------------------------------------------------------------------------- +// include files +// ----------------------------------------------------------------------------- + +#include "cholmod.h" +#include "UFconfig.h" +#include "SuiteSparseQR_definitions.h" + +// ============================================================================= +// === spqr_symbolic =========================================================== +// ============================================================================= + +// The contents of this object do not change during numeric factorization. The +// Symbolic object depends only on the pattern of the input matrix, and not its +// values. These contents also do not change with column pivoting for rank +// detection. This makes parallelism easier to manage, since all threads can +// have access to this object without synchronization. +// +// The total size of the Symbolic object is (10 + 2*m + anz + 2*n + 5*nf + rnz) +// Int's, where the user's input A matrix is m-by-n with anz nonzeros, nf <= +// MIN(m,n) is the number of frontal matrices, and rnz <= nnz(R) is the number +// of column indices used to represent the supernodal form of R (one Int per +// non-pivotal column index in the leading row of each block of R). + +struct spqr_symbolic +{ + + // ------------------------------------------------------------------------- + // row-form of the input matrix and its permutations + // ------------------------------------------------------------------------- + + // During symbolic analysis, the nonzero pattern of S = A(P,Q) is + // constructed, where A is the user's input matrix. Its numerical values + // are also constructed, but they do not become part of the Symbolic + // object. The matrix S is stored in row-oriented form. The rows of S are + // sorted according to their leftmost column index (via PLinv). Column + // indices in each row of S are in strictly ascending order, even though + // the input matrix A need not be sorted. + + UF_long m, n, anz ; // S is m-by-n with anz entries + + UF_long *Sp ; // size m+1, row pointers of S + + UF_long *Sj ; // size anz = Sp [n], column indices of S + + UF_long *Qfill ; // size n, fill-reducing column permutation. + // Qfill [k] = j if column k of A is column j of S. + + UF_long *PLinv ; // size m, inverse row permutation that places S=A(P,Q) + // in increasing order of leftmost column index. + // PLinv [i] = k if row i of A is row k of S. + + UF_long *Sleft ; // size n+2. The list of rows of S whose leftmost + // column index is j is given by + // Sleft [j] ... Sleft [j+1]-1. This can be empty (that is, Sleft + // [j] can equal Sleft [j+1]). Sleft [n] is the number of + // non-empty rows of S, and Sleft [n+1] == m. That is, Sleft [n] + // ... Sleft [n+1]-1 gives the empty rows of S, if any. + + // ------------------------------------------------------------------------- + // frontal matrices: pattern and tree + // ------------------------------------------------------------------------- + + // Each frontal matrix is fm-by-fn, with fnpiv pivot columns. The fn + // column indices are given by a set of size fnpiv pivot columns, defined + // by Super, followed by the pattern Rj [ Rp[f] ... Rp[f+1]-1 ]. + + // The row indices of the front are not kept. If the Householder vectors + // are not kept, the row indices are not needed. If the Householder + // vectors are kept, the row indices are computed dynamically during + // numerical factorization. + + UF_long nf ; // number of frontal matrices; nf <= MIN (m,n) + UF_long maxfn ; // max # of columns in any front + + // parent, child, and childp define the row merge tree or etree (A'A) + UF_long *Parent ; // size nf+1 + UF_long *Child ; // size nf+1 + UF_long *Childp ; // size nf+2 + + // The parent of a front f is Parent [f], or EMPTY if f=nf. + // A list of children of f can be obtained in the list + // Child [Childp [f] ... Childp [f+1]-1]. + + // Node nf in the tree is a placeholder; it does not represent a frontal + // matrix. All roots of the frontal "tree" (may be a forest) have the + // placeholder node nf as their parent. Thus, the tree of nodes 0:nf is + // truly a tree, with just one parent (node nf). + + UF_long *Super ; // size nf+1. Super [f] gives the first pivot column + // in the front F. This refers to a column of S. The + // number of expected pivot columns in F is thus + // Super [f+1] - Super [f]. + + UF_long *Rp ; // size nf+1 + UF_long *Rj ; // size rjsize; compressed supernodal form of R + + UF_long *Post ; // size nf+1, post ordering of frontal tree. f=Post[k] + // gives the kth node in the postordered tree + + UF_long rjsize ; // size of Rj + + UF_long do_rank_detection ; // TRUE: allow for tol >= 0. FALSE: ignore tol + + // the rest depends on whether or not rank-detection is allowed: + UF_long maxstack ; // max stack size (sequential case) + UF_long hisize ; // size of Hii + + UF_long keepH ; // TRUE if H is present + + UF_long *Hip ; // size nf+1. If H is kept, the row indices of frontal + // matrix f are in Hii [Hip [f] ... Hip [f] + Hm [f]], + // where Hii and Hm are stored in the numeric object. + + // There is one block row of R per frontal matrix. + // The fn column indices of R are given by Rj [Rp [f] ... Rp [f+1]-1], + // where the first fp column indices are Super [f] ... Super [f+1]-1. + // The remaining column indices in Rj [...] are non-pivotal, and are + // in the range Super [f+1] to n. The number of rows of R is at + // most fp, but can be less if dead columns appear in the matrix. + // The number of columns in the contribution block C is always + // cn = fn - fp, where fn = Rp [f+1] - Rp [f]. + + UF_long ntasks ; // number of tasks in task graph + UF_long ns ; // number of stacks + + // ------------------------------------------------------------------------- + // the rest of the QR symbolic object is present only if ntasks > 1 + // ------------------------------------------------------------------------- + + // Task tree (nodes 0:ntasks), including placeholder node + UF_long *TaskChildp ; // size ntasks+2 + UF_long *TaskChild ; // size ntasks+1 + + UF_long *TaskStack ; // size ntasks+1 + + // list of fronts for each task + UF_long *TaskFront ; // size nf+1 + UF_long *TaskFrontp ; // size ntasks+2 + + UF_long *On_stack ; // size nf+1, front f is on stack On_stack [f] + + // size of each stack + UF_long *Stack_maxstack ; // size ns+2 + +} ; + + +// ============================================================================= +// === spqr_numeric ============================================================ +// ============================================================================= + +// The Numeric object contains the numerical values of the triangular/ +// trapezoidal factor R, and optionally the Householder vectors H if they +// are kept. + +template struct spqr_numeric +{ + + // ------------------------------------------------------------------------- + // Numeric R factor + // ------------------------------------------------------------------------- + + Entry **Rblock ; // size nf. R [f] is an (Entry *) pointer to the + // R block for front F. It is an upper trapezoidal + // of size Rm(f)-by-Rn(f), but only the upper + // triangular part is stored in column-packed format. + + Entry **Stacks ; // size ns; an array of stacks holding the R and H + // factors and the current frontal matrix F at the head. + // This is followed by empty space, then the C blocks of + // prior frontal matrices at the bottom. When the + // factorization is complete, only the R and H part at + // the head of each stack is left. + + UF_long *Stack_size ; // size ns; Stack_size [s] is the size of Stacks [s] + + UF_long hisize ; // size of Hii + + UF_long n ; // A is m-by-n + UF_long m ; + UF_long nf ; // number of frontal matrices + UF_long ntasks ; // number of tasks in task graph actually used + UF_long ns ; // number of stacks actually used + UF_long maxstack ; // size of sequential stack, if used + + // ------------------------------------------------------------------------- + // for rank detection and m < n case + // ------------------------------------------------------------------------- + + char *Rdead ; // size n, Rdead [k] = 1 if k is a dead pivot column, + // Rdead [k] = 0 otherwise. If no columns are dead, + // this is NULL. If m < n, then at least m-n columns + // will be dead. + + UF_long rank ; // number of live pivot columns + UF_long rank1 ; // number of live pivot columns in first ntol columns + // of A + + UF_long maxfrank ; // max number of rows in any R block + + double norm_E_fro ; // 2-norm of w, the vector of dead column 2-norms + + // ------------------------------------------------------------------------- + // for keeping Householder vectors + // ------------------------------------------------------------------------- + + // The factorization is R = (H_s * ... * H_2 * H_1) * P_H + // where P_H is the permutation HPinv, and H_1, ... H_s are the Householder + // vectors (s = rjsize). + + UF_long keepH ; // TRUE if H is present + + UF_long rjsize ; // size of Hstair and HTau + + UF_long *HStair ; // size rjsize. The list Hstair [Rp [f] ... Rp [f+1]-1] + // gives the staircase for front F + + Entry *HTau ; // size rjsize. The list HTau [Rp [f] ... Rp [f+1]-1] + // gives the Householder coefficients for front F + + UF_long *Hii ; // size hisize, row indices of H. + + UF_long *HPinv ; // size m. HPinv [i] = k if row i of A and H is row k + // of R. This permutation includes QRsym->PLinv, and + // the permutation constructed via pivotal row ordering + // during factorization. + + UF_long *Hm ; // size nf, Hm [f] = # of rows in front F + UF_long *Hr ; // size nf, Hr [f] = # of rows in R block of front F + UF_long maxfm ; // max (Hm [0:nf-1]), computed only if H kept + +} ; + + +// ============================================================================= +// === SuiteSparseQR_factorization ============================================= +// ============================================================================= + +// A combined symbolic+numeric QR factorization of A or [A B], +// with singletons + +template struct SuiteSparseQR_factorization +{ + + // QR factorization of A or [A Binput] after singletons have been removed + double tol ; // tol used + spqr_symbolic *QRsym ; + spqr_numeric *QRnum ; + + // singletons, in compressed-row form; R is n1rows-by-n + UF_long *R1p ; // size n1rows+1 + UF_long *R1j ; + Entry *R1x ; + UF_long r1nz ; // nnz (R1) + + // combined singleton and fill-reducing permutation + UF_long *Q1fill ; + UF_long *P1inv ; + UF_long *HP1inv ; // NULL if n1cols == 0, in which case QRnum->HPinv + // serves in its place. + + // Rmap and RmapInv are NULL if QR->rank == A->ncol + UF_long *Rmap ; // size n. Rmap [j] = k if column j of R is the kth + // live column and where k < QR->rank; otherwise, if + // j is a dead column, then k >= QR->rank. + UF_long *RmapInv ; + + UF_long n1rows ; // number of singleton rows of [A B] + UF_long n1cols ; // number of singleton columns of [A B] + + UF_long narows ; // number of rows of A + UF_long nacols ; // number of columns of A + UF_long bncols ; // number of columns of B + UF_long rank ; // rank estimate of A (n1rows + QRnum->rank1), ranges + // from 0 to min(m,n) + + int allow_tol ; // if TRUE, do rank detection +} ; + + +// ============================================================================= +// === Simple user-callable SuiteSparseQR functions ============================ +// ============================================================================= + +// SuiteSparseQR Sparse QR factorization and solve +// SuiteSparseQR_qmult Q*X, Q'*X, X*Q, or X*Q' for X full or sparse + +// returns rank(A) estimate, or EMPTY on failure +template UF_long SuiteSparseQR +( + // inputs, not modified + int ordering, // all, except 3:given treated as 0:fixed + double tol, // only accept singletons above tol + + UF_long econ, // number of rows of C and R to return; a value + // less than the rank r of A is treated as r, and + // a value greater than m is treated as m. + + int getCTX, // if 0: return Z = C of size econ-by-bncols + // if 1: return Z = C' of size bncols-by-econ + // if 2: return Z = X of size econ-by-bncols + + cholmod_sparse *A, // m-by-n sparse matrix + + // B is either sparse or dense. If Bsparse is non-NULL, B is sparse and + // Bdense is ignored. If Bsparse is NULL and Bdense is non-NULL, then B is + // dense. B is not present if both are NULL. + cholmod_sparse *Bsparse, + cholmod_dense *Bdense, + + // output arrays, neither allocated nor defined on input. + + // Z is the matrix C, C', or X + cholmod_sparse **Zsparse, + cholmod_dense **Zdense, + cholmod_sparse **R, // the R factor + UF_long **E, // size n; fill-reducing ordering of A. + cholmod_sparse **H, // the Householder vectors (m-by-nh) + UF_long **HPinv, // size m; row permutation for H + cholmod_dense **HTau, // size nh, Householder coefficients + + // workspace and parameters + cholmod_common *cc +) ; + +// X = A\dense(B) +template cholmod_dense *SuiteSparseQR +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + cholmod_sparse *A, // m-by-n sparse matrix + cholmod_dense *B, // m-by-nrhs + cholmod_common *cc // workspace and parameters +) ; + +// X = A\dense(B) using default ordering and tolerance +template cholmod_dense *SuiteSparseQR +( + cholmod_sparse *A, // m-by-n sparse matrix + cholmod_dense *B, // m-by-nrhs + cholmod_common *cc // workspace and parameters +) ; + +// X = A\sparse(B) +template cholmod_sparse *SuiteSparseQR +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + cholmod_sparse *A, // m-by-n sparse matrix + cholmod_sparse *B, // m-by-nrhs + cholmod_common *cc // workspace and parameters +) ; + +// [Q,R,E] = qr(A), returning Q as a sparse matrix +template UF_long SuiteSparseQR // returns rank(A) estimate +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + UF_long econ, + cholmod_sparse *A, // m-by-n sparse matrix + // outputs + cholmod_sparse **Q, // m-by-e sparse matrix where e=max(econ,rank(A)) + cholmod_sparse **R, // e-by-n sparse matrix + UF_long **E, // permutation of 0:n-1, NULL if identity + cholmod_common *cc // workspace and parameters +) ; + +// [Q,R,E] = qr(A), discarding Q +template UF_long SuiteSparseQR // returns rank(A) estimate +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + UF_long econ, + cholmod_sparse *A, // m-by-n sparse matrix + // outputs + cholmod_sparse **R, // e-by-n sparse matrix + UF_long **E, // permutation of 0:n-1, NULL if identity + cholmod_common *cc // workspace and parameters +) ; + +// [C,R,E] = qr(A,B), where C and B are dense +template UF_long SuiteSparseQR +( + // inputs, not modified + int ordering, // all, except 3:given treated as 0:fixed + double tol, // only accept singletons above tol + UF_long econ, // number of rows of C and R to return + cholmod_sparse *A, // m-by-n sparse matrix + cholmod_dense *B, // m-by-nrhs dense matrix + // outputs + cholmod_dense **C, // C = Q'*B, an e-by-nrhs dense matrix + cholmod_sparse **R, // e-by-n sparse matrix where e=max(econ,rank(A)) + UF_long **E, // permutation of 0:n-1, NULL if identity + cholmod_common *cc // workspace and parameters +) ; + +// [C,R,E] = qr(A,B), where C and B are sparse +template UF_long SuiteSparseQR +( + // inputs, not modified + int ordering, // all, except 3:given treated as 0:fixed + double tol, // only accept singletons above tol + UF_long econ, // number of rows of C and R to return + cholmod_sparse *A, // m-by-n sparse matrix + cholmod_sparse *B, // m-by-nrhs sparse matrix + // outputs + cholmod_sparse **C, // C = Q'*B, an e-by-nrhs sparse matrix + cholmod_sparse **R, // e-by-n sparse matrix where e=max(econ,rank(A)) + UF_long **E, // permutation of 0:n-1, NULL if identity + cholmod_common *cc // workspace and parameters +) ; + +// [Q,R,E] = qr(A) where Q is returned in Householder form +template UF_long SuiteSparseQR +( + // inputs, not modified + int ordering, // all, except 3:given treated as 0:fixed + double tol, // only accept singletons above tol + UF_long econ, // number of rows of C and R to return + cholmod_sparse *A, // m-by-n sparse matrix + // outputs + cholmod_sparse **R, // the R factor + UF_long **E, // permutation of 0:n-1, NULL if identity + cholmod_sparse **H, // the Householder vectors (m-by-nh) + UF_long **HPinv, // size m; row permutation for H + cholmod_dense **HTau, // size nh, Householder coefficients + cholmod_common *cc // workspace and parameters +) ; + +// ============================================================================= +// === SuiteSparseQR_qmult ===================================================== +// ============================================================================= + +// This function takes as input the matrix Q in Householder form, as returned +// by SuiteSparseQR (... H, HPinv, HTau, cc) above. + +// returns Y of size m-by-n (NULL on failure) +template cholmod_dense *SuiteSparseQR_qmult +( + // inputs, no modified + int method, // 0,1,2,3 + cholmod_sparse *H, // either m-by-nh or n-by-nh + cholmod_dense *HTau, // size 1-by-nh + UF_long *HPinv, // size mh + cholmod_dense *Xdense, // size m-by-n + + // workspace and parameters + cholmod_common *cc +) ; + +template cholmod_sparse *SuiteSparseQR_qmult +( + // inputs, no modified + int method, // 0,1,2,3 + cholmod_sparse *H, // either m-by-nh or n-by-nh + cholmod_dense *HTau, // size 1-by-nh + UF_long *HPinv, // size mh + cholmod_sparse *X, + + // workspace and parameters + cholmod_common *cc +) ; + +// ============================================================================= +// === Expert user-callable SuiteSparseQR functions ============================ +// ============================================================================= + +#ifndef NEXPERT + +// These functions are "expert" routines, allowing reuse of the QR +// factorization for different right-hand-sides. They also allow the user to +// find the minimum 2-norm solution to an undertermined system of equations. + +template +SuiteSparseQR_factorization *SuiteSparseQR_factorize +( + // inputs, not modified: + int ordering, // all, except 3:given treated as 0:fixed + double tol, // treat columns with 2-norm <= tol as zero + cholmod_sparse *A, // sparse matrix to factorize + // workspace and parameters + cholmod_common *cc +) ; + +template cholmod_dense *SuiteSparseQR_solve // returns X +( + // inputs, not modified: + int system, // which system to solve + SuiteSparseQR_factorization *QR, // of an m-by-n sparse matrix A + cholmod_dense *B, // right-hand-side, m-by-nrhs or n-by-nrhs + // workspace and parameters + cholmod_common *cc +) ; + +template cholmod_sparse *SuiteSparseQR_solve // returns X +( + // inputs, not modified: + int system, // which system to solve (0,1,2,3) + SuiteSparseQR_factorization *QR, // of an m-by-n sparse matrix A + cholmod_sparse *Bsparse, // right-hand-side, m-by-nrhs or n-by-nrhs + // workspace and parameters + cholmod_common *cc +) ; + +// returns Y of size m-by-n, or NULL on failure +template cholmod_dense *SuiteSparseQR_qmult +( + // inputs, not modified + int method, // 0,1,2,3 (same as SuiteSparseQR_qmult) + SuiteSparseQR_factorization *QR, // of an m-by-n sparse matrix A + cholmod_dense *Xdense, // size m-by-n with leading dimension ldx + // workspace and parameters + cholmod_common *cc +) ; + +// returns Y of size m-by-n, or NULL on failure +template cholmod_sparse *SuiteSparseQR_qmult +( + // inputs, not modified + int method, // 0,1,2,3 + SuiteSparseQR_factorization *QR, // of an m-by-n sparse matrix A + cholmod_sparse *Xsparse, // size m-by-n + // workspace and parameters + cholmod_common *cc +) ; + +// free the QR object +template int SuiteSparseQR_free +( + SuiteSparseQR_factorization **QR, // of an m-by-n sparse matrix A + cholmod_common *cc +) ; + +// find the min 2-norm solution to a sparse linear system +template cholmod_dense *SuiteSparseQR_min2norm +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + cholmod_sparse *A, + cholmod_dense *B, + cholmod_common *cc +) ; + +template cholmod_sparse *SuiteSparseQR_min2norm +( + int ordering, // all, except 3:given treated as 0:fixed + double tol, + cholmod_sparse *A, + cholmod_sparse *B, + cholmod_common *cc +) ; + +// symbolic QR factorization; no singletons exploited +template +SuiteSparseQR_factorization *SuiteSparseQR_symbolic +( + // inputs: + int ordering, // all, except 3:given treated as 0:fixed + int allow_tol, // if FALSE, tol is ignored by the numeric + // factorization, and no rank detection is performed + cholmod_sparse *A, // sparse matrix to factorize (A->x ignored) + cholmod_common *cc // workspace and parameters +) ; + +// numeric QR factorization; +template int SuiteSparseQR_numeric +( + // inputs: + double tol, // treat columns with 2-norm <= tol as zero + cholmod_sparse *A, // sparse matrix to factorize + // input/output + SuiteSparseQR_factorization *QR, + cholmod_common *cc // workspace and parameters +) ; + +#endif + +// ============================================================================= +// === high-resolution timing ================================================== +// ============================================================================= + +#ifdef TIMING + +extern "C" { + +#include +#include + +double spqr_time ( ) ; // returns current time in seconds + +} +#endif + +#endif diff --git a/spqr_mini/UFconfig.h b/spqr_mini/UFconfig.h new file mode 100644 index 000000000..5b39627a3 --- /dev/null +++ b/spqr_mini/UFconfig.h @@ -0,0 +1,151 @@ +/* ========================================================================== */ +/* === UFconfig.h =========================================================== */ +/* ========================================================================== */ + +/* Configuration file for SuiteSparse: a Suite of Sparse matrix packages + * (AMD, COLAMD, CCOLAMD, CAMD, CHOLMOD, UMFPACK, CXSparse, and others). + * + * UFconfig.h provides the definition of the long integer. On most systems, + * a C program can be compiled in LP64 mode, in which long's and pointers are + * both 64-bits, and int's are 32-bits. Windows 64, however, uses the LLP64 + * model, in which int's and long's are 32-bits, and long long's and pointers + * are 64-bits. + * + * SuiteSparse packages that include long integer versions are + * intended for the LP64 mode. However, as a workaround for Windows 64 + * (and perhaps other systems), the long integer can be redefined. + * + * If _WIN64 is defined, then the __int64 type is used instead of long. + * + * The long integer can also be defined at compile time. For example, this + * could be added to UFconfig.mk: + * + * CFLAGS = -O -D'UF_long=long long' -D'UF_long_max=9223372036854775801' \ + * -D'UF_long_idd="lld"' + * + * This file defines UF_long as either long (on all but _WIN64) or + * __int64 on Windows 64. The intent is that a UF_long is always a 64-bit + * integer in a 64-bit code. ptrdiff_t might be a better choice than long; + * it is always the same size as a pointer. + * + * This file also defines the SUITESPARSE_VERSION and related definitions. + * + * Copyright (c) 2007, University of Florida. No licensing restrictions + * apply to this file or to the UFconfig directory. Author: Timothy A. Davis. + */ + +#ifndef _UFCONFIG_H +#define _UFCONFIG_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +/* ========================================================================== */ +/* === UF_long ============================================================== */ +/* ========================================================================== */ + +#ifndef UF_long + +#ifdef _WIN64 + +#define UF_long __int64 +#define UF_long_max _I64_MAX +#define UF_long_idd "I64d" + +#else + +#define UF_long long +#define UF_long_max LONG_MAX +#define UF_long_idd "ld" + +#endif +#define UF_long_id "%" UF_long_idd +#endif + +/* ========================================================================== */ +/* === UFconfig parameters and functions ==================================== */ +/* ========================================================================== */ + +/* SuiteSparse-wide parameters will be placed in this struct. So far, they + are only used by RBio. */ + +typedef struct UFconfig_struct +{ + void *(*malloc_memory) (size_t) ; /* pointer to malloc */ + void *(*realloc_memory) (void *, size_t) ; /* pointer to realloc */ + void (*free_memory) (void *) ; /* pointer to free */ + void *(*calloc_memory) (size_t, size_t) ; /* pointer to calloc */ + +} UFconfig ; + +void *UFmalloc /* pointer to allocated block of memory */ +( + size_t nitems, /* number of items to malloc (>=1 is enforced) */ + size_t size_of_item, /* sizeof each item */ + int *ok, /* TRUE if successful, FALSE otherwise */ + UFconfig *config /* SuiteSparse-wide configuration */ +) ; + +void *UFfree /* always returns NULL */ +( + void *p, /* block to free */ + UFconfig *config /* SuiteSparse-wide configuration */ +) ; + + +/* ========================================================================== */ +/* === SuiteSparse version ================================================== */ +/* ========================================================================== */ + +/* SuiteSparse is not a package itself, but a collection of packages, some of + * which must be used together (UMFPACK requires AMD, CHOLMOD requires AMD, + * COLAMD, CAMD, and CCOLAMD, etc). A version number is provided here for the + * collection itself. The versions of packages within each version of + * SuiteSparse are meant to work together. Combining one packge from one + * version of SuiteSparse, with another package from another version of + * SuiteSparse, may or may not work. + * + * SuiteSparse Version 3.5.0 contains the following packages: + * + * AMD version 2.2.1 + * BTF version 1.1.1 + * CAMD version 2.2.1 + * CCOLAMD version 2.7.2 + * CHOLMOD version 1.7.2 + * COLAMD version 2.7.2 + * CSparse version 2.2.4 + * CXSparse version 2.2.4 + * KLU version 1.1.1 + * LDL version 2.0.2 + * RBio version 2.0.0 + * SuiteSparseQR version 1.2.0 + * UFcollection version 1.3.0 + * UFconfig version number is the same as SuiteSparse + * UMFPACK version 5.5.0 + * LINFACTOR version 1.1.0 + * MESHND version 1.1.1 + * SSMULT version 2.0.2 + * MATLAB_Tools no specific version number + * + * Other package dependencies: + * BLAS required by CHOLMOD and UMFPACK + * LAPACK required by CHOLMOD + * METIS 4.0.1 required by CHOLMOD (optional) and KLU (optional) + */ + +#define SUITESPARSE_DATE "Nov 30, 2009" +#define SUITESPARSE_VER_CODE(main,sub) ((main) * 1000 + (sub)) +#define SUITESPARSE_MAIN_VERSION 3 +#define SUITESPARSE_SUB_VERSION 5 +#define SUITESPARSE_SUBSUB_VERSION 1 +#define SUITESPARSE_VERSION \ + SUITESPARSE_VER_CODE(SUITESPARSE_MAIN_VERSION,SUITESPARSE_SUB_VERSION) + +#ifdef __cplusplus +} +#endif +#endif diff --git a/spqr_mini/cholmod_blas.h b/spqr_mini/cholmod_blas.h new file mode 100644 index 000000000..b03de64fe --- /dev/null +++ b/spqr_mini/cholmod_blas.h @@ -0,0 +1,456 @@ +/* ========================================================================== */ +/* === Include/cholmod_blas.h =============================================== */ +/* ========================================================================== */ + +/* ----------------------------------------------------------------------------- + * CHOLMOD/Include/cholmod_blas.h. + * Copyright (C) 2005-2006, Univ. of Florida. Author: Timothy A. Davis + * CHOLMOD/Include/cholmod_blas.h is licensed under Version 2.1 of the GNU + * Lesser General Public License. See lesser.txt for a text of the license. + * CHOLMOD is also available under other licenses; contact authors for details. + * http://www.cise.ufl.edu/research/sparse + * -------------------------------------------------------------------------- */ + +/* This does not need to be included in the user's program. */ + +#ifndef CHOLMOD_BLAS_H +#define CHOLMOD_BLAS_H + +/* ========================================================================== */ +/* === Architecture ========================================================= */ +/* ========================================================================== */ + +#if defined (__sun) || defined (MSOL2) || defined (ARCH_SOL2) +#define CHOLMOD_SOL2 +#define CHOLMOD_ARCHITECTURE "Sun Solaris" + +#elif defined (__sgi) || defined (MSGI) || defined (ARCH_SGI) +#define CHOLMOD_SGI +#define CHOLMOD_ARCHITECTURE "SGI Irix" + +#elif defined (__linux) || defined (MGLNX86) || defined (ARCH_GLNX86) +#define CHOLMOD_LINUX +#define CHOLMOD_ARCHITECTURE "Linux" + +#elif defined (__APPLE__) +#define CHOLMOD_MAC +#define CHOLMOD_ARCHITECTURE "Mac" + +#elif defined (_AIX) || defined (MIBM_RS) || defined (ARCH_IBM_RS) +#define CHOLMOD_AIX +#define CHOLMOD_ARCHITECTURE "IBM AIX" +/* recent reports from IBM AIX seem to indicate that this is not needed: */ +/* #define BLAS_NO_UNDERSCORE */ + +#elif defined (__alpha) || defined (MALPHA) || defined (ARCH_ALPHA) +#define CHOLMOD_ALPHA +#define CHOLMOD_ARCHITECTURE "Compaq Alpha" + +#elif defined (_WIN32) || defined (WIN32) || defined (_WIN64) || defined (WIN64) +#if defined (__MINGW32__) || defined (__MINGW32__) +#define CHOLMOD_MINGW +#elif defined (__CYGWIN32__) || defined (__CYGWIN32__) +#define CHOLMOD_CYGWIN +#else +#define CHOLMOD_WINDOWS +#define BLAS_NO_UNDERSCORE +#endif +#define CHOLMOD_ARCHITECTURE "Microsoft Windows" + +#elif defined (__hppa) || defined (__hpux) || defined (MHPUX) || defined (ARCH_HPUX) +#define CHOLMOD_HP +#define CHOLMOD_ARCHITECTURE "HP Unix" +#define BLAS_NO_UNDERSCORE + +#elif defined (__hp700) || defined (MHP700) || defined (ARCH_HP700) +#define CHOLMOD_HP +#define CHOLMOD_ARCHITECTURE "HP 700 Unix" +#define BLAS_NO_UNDERSCORE + +#else +/* If the architecture is unknown, and you call the BLAS, you may need to */ +/* define BLAS_BY_VALUE, BLAS_NO_UNDERSCORE, and/or BLAS_CHAR_ARG yourself. */ +#define CHOLMOD_ARCHITECTURE "unknown" +#endif + +/* ========================================================================== */ +/* === BLAS and LAPACK names ================================================ */ +/* ========================================================================== */ + +/* Prototypes for the various versions of the BLAS. */ + +/* Determine if the 64-bit Sun Performance BLAS is to be used */ +#if defined(CHOLMOD_SOL2) && !defined(NSUNPERF) && defined(BLAS64) +#define SUN64 +#endif + +#ifdef SUN64 + +#define BLAS_DTRSV dtrsv_64_ +#define BLAS_DGEMV dgemv_64_ +#define BLAS_DTRSM dtrsm_64_ +#define BLAS_DGEMM dgemm_64_ +#define BLAS_DSYRK dsyrk_64_ +#define BLAS_DGER dger_64_ +#define BLAS_DSCAL dscal_64_ +#define LAPACK_DPOTRF dpotrf_64_ + +#define BLAS_ZTRSV ztrsv_64_ +#define BLAS_ZGEMV zgemv_64_ +#define BLAS_ZTRSM ztrsm_64_ +#define BLAS_ZGEMM zgemm_64_ +#define BLAS_ZHERK zherk_64_ +#define BLAS_ZGER zgeru_64_ +#define BLAS_ZSCAL zscal_64_ +#define LAPACK_ZPOTRF zpotrf_64_ + +#elif defined (BLAS_NO_UNDERSCORE) + +#define BLAS_DTRSV dtrsv +#define BLAS_DGEMV dgemv +#define BLAS_DTRSM dtrsm +#define BLAS_DGEMM dgemm +#define BLAS_DSYRK dsyrk +#define BLAS_DGER dger +#define BLAS_DSCAL dscal +#define LAPACK_DPOTRF dpotrf + +#define BLAS_ZTRSV ztrsv +#define BLAS_ZGEMV zgemv +#define BLAS_ZTRSM ztrsm +#define BLAS_ZGEMM zgemm +#define BLAS_ZHERK zherk +#define BLAS_ZGER zgeru +#define BLAS_ZSCAL zscal +#define LAPACK_ZPOTRF zpotrf + +#else + +#define BLAS_DTRSV dtrsv_ +#define BLAS_DGEMV dgemv_ +#define BLAS_DTRSM dtrsm_ +#define BLAS_DGEMM dgemm_ +#define BLAS_DSYRK dsyrk_ +#define BLAS_DGER dger_ +#define BLAS_DSCAL dscal_ +#define LAPACK_DPOTRF dpotrf_ + +#define BLAS_ZTRSV ztrsv_ +#define BLAS_ZGEMV zgemv_ +#define BLAS_ZTRSM ztrsm_ +#define BLAS_ZGEMM zgemm_ +#define BLAS_ZHERK zherk_ +#define BLAS_ZGER zgeru_ +#define BLAS_ZSCAL zscal_ +#define LAPACK_ZPOTRF zpotrf_ + +#endif + +/* ========================================================================== */ +/* === BLAS and LAPACK integer arguments ==================================== */ +/* ========================================================================== */ + +/* Compile CHOLMOD, UMFPACK, and SPQR with -DBLAS64 if you have a BLAS that + * uses 64-bit integers */ + +#if defined (LONGBLAS) || defined (BLAS64) +#define BLAS_INT UF_long +#else +#define BLAS_INT int +#endif + +/* If the BLAS integer is smaller than the basic CHOLMOD integer, then we need + * to check for integer overflow when converting from Int to BLAS_INT. If + * any integer overflows, the externally-defined BLAS_OK variable is + * set to FALSE. BLAS_OK should be set to TRUE before calling any + * BLAS_* macro. + */ + +#define CHECK_BLAS_INT (sizeof (BLAS_INT) < sizeof (Int)) +#define EQ(K,k) (((BLAS_INT) K) == ((Int) k)) + +/* ========================================================================== */ +/* === BLAS and LAPACK prototypes and macros ================================ */ +/* ========================================================================== */ + +void BLAS_DGEMV (char *trans, BLAS_INT *m, BLAS_INT *n, double *alpha, + double *A, BLAS_INT *lda, double *X, BLAS_INT *incx, double *beta, + double *Y, BLAS_INT *incy) ; + +#define BLAS_dgemv(trans,m,n,alpha,A,lda,X,incx,beta,Y,incy) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, INCX = incx, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (INCX,incx) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DGEMV (trans, &M, &N, alpha, A, &LDA, X, &INCX, beta, Y, &INCY) ; \ + } \ +} + +void BLAS_ZGEMV (char *trans, BLAS_INT *m, BLAS_INT *n, double *alpha, + double *A, BLAS_INT *lda, double *X, BLAS_INT *incx, double *beta, + double *Y, BLAS_INT *incy) ; + +#define BLAS_zgemv(trans,m,n,alpha,A,lda,X,incx,beta,Y,incy) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, INCX = incx, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (INCX,incx) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZGEMV (trans, &M, &N, alpha, A, &LDA, X, &INCX, beta, Y, &INCY) ; \ + } \ +} + +void BLAS_DTRSV (char *uplo, char *trans, char *diag, BLAS_INT *n, double *A, + BLAS_INT *lda, double *X, BLAS_INT *incx) ; + +#define BLAS_dtrsv(uplo,trans,diag,n,A,lda,X,incx) \ +{ \ + BLAS_INT N = n, LDA = lda, INCX = incx ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (LDA,lda) && EQ (INCX,incx))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DTRSV (uplo, trans, diag, &N, A, &LDA, X, &INCX) ; \ + } \ +} + +void BLAS_ZTRSV (char *uplo, char *trans, char *diag, BLAS_INT *n, double *A, + BLAS_INT *lda, double *X, BLAS_INT *incx) ; + +#define BLAS_ztrsv(uplo,trans,diag,n,A,lda,X,incx) \ +{ \ + BLAS_INT N = n, LDA = lda, INCX = incx ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (LDA,lda) && EQ (INCX,incx))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZTRSV (uplo, trans, diag, &N, A, &LDA, X, &INCX) ; \ + } \ +} + +void BLAS_DTRSM (char *side, char *uplo, char *transa, char *diag, BLAS_INT *m, + BLAS_INT *n, double *alpha, double *A, BLAS_INT *lda, double *B, + BLAS_INT *ldb) ; + +#define BLAS_dtrsm(side,uplo,transa,diag,m,n,alpha,A,lda,B,ldb) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, LDB = ldb ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (LDB,ldb))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DTRSM (side, uplo, transa, diag, &M, &N, alpha, A, &LDA, B, &LDB);\ + } \ +} + +void BLAS_ZTRSM (char *side, char *uplo, char *transa, char *diag, BLAS_INT *m, + BLAS_INT *n, double *alpha, double *A, BLAS_INT *lda, double *B, + BLAS_INT *ldb) ; + +#define BLAS_ztrsm(side,uplo,transa,diag,m,n,alpha,A,lda,B,ldb) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, LDB = ldb ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (LDB,ldb))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZTRSM (side, uplo, transa, diag, &M, &N, alpha, A, &LDA, B, &LDB);\ + } \ +} + +void BLAS_DGEMM (char *transa, char *transb, BLAS_INT *m, BLAS_INT *n, + BLAS_INT *k, double *alpha, double *A, BLAS_INT *lda, double *B, + BLAS_INT *ldb, double *beta, double *C, BLAS_INT *ldc) ; + +#define BLAS_dgemm(transa,transb,m,n,k,alpha,A,lda,B,ldb,beta,C,ldc) \ +{ \ + BLAS_INT M = m, N = n, K = k, LDA = lda, LDB = ldb, LDC = ldc ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (K,k) && \ + EQ (LDA,lda) && EQ (LDB,ldb) && EQ (LDC,ldc))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DGEMM (transa, transb, &M, &N, &K, alpha, A, &LDA, B, &LDB, beta, \ + C, &LDC) ; \ + } \ +} + +void BLAS_ZGEMM (char *transa, char *transb, BLAS_INT *m, BLAS_INT *n, + BLAS_INT *k, double *alpha, double *A, BLAS_INT *lda, double *B, + BLAS_INT *ldb, double *beta, double *C, BLAS_INT *ldc) ; + +#define BLAS_zgemm(transa,transb,m,n,k,alpha,A,lda,B,ldb,beta,C,ldc) \ +{ \ + BLAS_INT M = m, N = n, K = k, LDA = lda, LDB = ldb, LDC = ldc ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (K,k) && \ + EQ (LDA,lda) && EQ (LDB,ldb) && EQ (LDC,ldc))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZGEMM (transa, transb, &M, &N, &K, alpha, A, &LDA, B, &LDB, beta, \ + C, &LDC) ; \ + } \ +} + +void BLAS_DSYRK (char *uplo, char *trans, BLAS_INT *n, BLAS_INT *k, + double *alpha, double *A, BLAS_INT *lda, double *beta, double *C, + BLAS_INT *ldc) ; + +#define BLAS_dsyrk(uplo,trans,n,k,alpha,A,lda,beta,C,ldc) \ +{ \ + BLAS_INT N = n, K = k, LDA = lda, LDC = ldc ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (K,k) && EQ (LDA,lda) && \ + EQ (LDC,ldc))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DSYRK (uplo, trans, &N, &K, alpha, A, &LDA, beta, C, &LDC) ; \ + } \ +} \ + +void BLAS_ZHERK (char *uplo, char *trans, BLAS_INT *n, BLAS_INT *k, + double *alpha, double *A, BLAS_INT *lda, double *beta, double *C, + BLAS_INT *ldc) ; + +#define BLAS_zherk(uplo,trans,n,k,alpha,A,lda,beta,C,ldc) \ +{ \ + BLAS_INT N = n, K = k, LDA = lda, LDC = ldc ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (K,k) && EQ (LDA,lda) && \ + EQ (LDC,ldc))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZHERK (uplo, trans, &N, &K, alpha, A, &LDA, beta, C, &LDC) ; \ + } \ +} \ + +void LAPACK_DPOTRF (char *uplo, BLAS_INT *n, double *A, BLAS_INT *lda, + BLAS_INT *info) ; + +#define LAPACK_dpotrf(uplo,n,A,lda,info) \ +{ \ + BLAS_INT N = n, LDA = lda, INFO = 1 ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (LDA,lda))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + LAPACK_DPOTRF (uplo, &N, A, &LDA, &INFO) ; \ + } \ + info = INFO ; \ +} + +void LAPACK_ZPOTRF (char *uplo, BLAS_INT *n, double *A, BLAS_INT *lda, + BLAS_INT *info) ; + +#define LAPACK_zpotrf(uplo,n,A,lda,info) \ +{ \ + BLAS_INT N = n, LDA = lda, INFO = 1 ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (LDA,lda))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + LAPACK_ZPOTRF (uplo, &N, A, &LDA, &INFO) ; \ + } \ + info = INFO ; \ +} + +/* ========================================================================== */ + +void BLAS_DSCAL (BLAS_INT *n, double *alpha, double *Y, BLAS_INT *incy) ; + +#define BLAS_dscal(n,alpha,Y,incy) \ +{ \ + BLAS_INT N = n, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DSCAL (&N, alpha, Y, &INCY) ; \ + } \ +} + +void BLAS_ZSCAL (BLAS_INT *n, double *alpha, double *Y, BLAS_INT *incy) ; + +#define BLAS_zscal(n,alpha,Y,incy) \ +{ \ + BLAS_INT N = n, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (N,n) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZSCAL (&N, alpha, Y, &INCY) ; \ + } \ +} + +void BLAS_DGER (BLAS_INT *m, BLAS_INT *n, double *alpha, + double *X, BLAS_INT *incx, double *Y, BLAS_INT *incy, + double *A, BLAS_INT *lda) ; + +#define BLAS_dger(m,n,alpha,X,incx,Y,incy,A,lda) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, INCX = incx, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (INCX,incx) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_DGER (&M, &N, alpha, X, &INCX, Y, &INCY, A, &LDA) ; \ + } \ +} + +void BLAS_ZGER (BLAS_INT *m, BLAS_INT *n, double *alpha, + double *X, BLAS_INT *incx, double *Y, BLAS_INT *incy, + double *A, BLAS_INT *lda) ; + +#define BLAS_zgeru(m,n,alpha,X,incx,Y,incy,A,lda) \ +{ \ + BLAS_INT M = m, N = n, LDA = lda, INCX = incx, INCY = incy ; \ + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDA,lda) && \ + EQ (INCX,incx) && EQ (INCY,incy))) \ + { \ + BLAS_OK = FALSE ; \ + } \ + if (!CHECK_BLAS_INT || BLAS_OK) \ + { \ + BLAS_ZGER (&M, &N, alpha, X, &INCX, Y, &INCY, A, &LDA) ; \ + } \ +} + +#endif diff --git a/spqr_mini/cholmod_common.c b/spqr_mini/cholmod_common.c new file mode 100644 index 000000000..06e873b26 --- /dev/null +++ b/spqr_mini/cholmod_common.c @@ -0,0 +1,672 @@ +/* ========================================================================== */ +/* === Core/cholmod_common ================================================== */ +/* ========================================================================== */ + +/* ----------------------------------------------------------------------------- + * CHOLMOD/Core Module. Copyright (C) 2005-2006, + * Univ. of Florida. Author: Timothy A. Davis + * The CHOLMOD/Core Module is licensed under Version 2.1 of the GNU + * Lesser General Public License. See lesser.txt for a text of the license. + * CHOLMOD is also available under other licenses; contact authors for details. + * http://www.cise.ufl.edu/research/sparse + * -------------------------------------------------------------------------- */ + +/* Core utility routines for the cholmod_common object: + * + * Primary routines: + * ----------------- + * cholmod_start the first call to CHOLMOD + * cholmod_finish the last call to CHOLMOD + * + * Secondary routines: + * ------------------- + * cholmod_defaults restore (most) default control parameters + * cholmod_allocate_work allocate (or reallocate) workspace in Common + * cholmod_free_work free workspace in Common + * cholmod_clear_flag clear Common->Flag in workspace + * cholmod_maxrank column dimension of Common->Xwork workspace + * + * The Common object is unique. It cannot be allocated or deallocated by + * CHOLMOD, since it contains the definition of the memory management routines + * used (pointers to malloc, free, realloc, and calloc, or their equivalent). + * The Common object contains workspace that is used between calls to + * CHOLMOD routines. This workspace allocated by CHOLMOD as needed, by + * cholmod_allocate_work and cholmod_free_work. + */ + +#include "cholmod_internal.h" +#include "cholmod_core.h" + +/* ========================================================================== */ +/* === cholmod_start ======================================================== */ +/* ========================================================================== */ + +/* Initialize Common default parameters and statistics. Sets workspace + * pointers to NULL. + * + * This routine must be called just once, prior to calling any other CHOLMOD + * routine. Do not call this routine after any other CHOLMOD routine (except + * cholmod_finish, to start a new CHOLMOD session), or a memory leak will + * occur. + * + * workspace: none + */ + +int CHOLMOD(start) +( + cholmod_common *Common +) +{ + int k ; + + if (Common == NULL) + { + return (FALSE) ; + } + + /* ---------------------------------------------------------------------- */ + /* user error handling routine */ + /* ---------------------------------------------------------------------- */ + + Common->error_handler = NULL ; + + /* ---------------------------------------------------------------------- */ + /* integer and numerical types */ + /* ---------------------------------------------------------------------- */ + + Common->itype = ITYPE ; + Common->dtype = DTYPE ; + + /* ---------------------------------------------------------------------- */ + /* default control parameters */ + /* ---------------------------------------------------------------------- */ + + cholmod_l_defaults(Common) ; + Common->try_catch = FALSE ; + + /* ---------------------------------------------------------------------- */ + /* memory management routines */ + /* ---------------------------------------------------------------------- */ + + /* The user can replace cholmod's memory management routines by redefining + * these function pointers. */ + +#ifndef NMALLOC + /* stand-alone ANSI C program */ + Common->malloc_memory = malloc ; + Common->free_memory = free ; + Common->realloc_memory = realloc ; + Common->calloc_memory = calloc ; +#else + /* no memory manager defined at compile-time; MUST define one at run-time */ + Common->malloc_memory = NULL ; + Common->free_memory = NULL ; + Common->realloc_memory = NULL ; + Common->calloc_memory = NULL ; +#endif + + /* ---------------------------------------------------------------------- */ + /* complex arithmetic routines */ + /* ---------------------------------------------------------------------- */ + +// Common->complex_divide = CHOLMOD(divcomplex) ; +// Common->hypotenuse = CHOLMOD(hypot) ; + + /* ---------------------------------------------------------------------- */ + /* print routine */ + /* ---------------------------------------------------------------------- */ + +#ifndef NPRINT + /* stand-alone ANSI C program */ + Common->print_function = printf ; +#else + /* printing disabled */ + Common->print_function = NULL ; +#endif + + /* ---------------------------------------------------------------------- */ + /* workspace */ + /* ---------------------------------------------------------------------- */ + + /* This code assumes the workspace held in Common is not initialized. If + * it is, then a memory leak will occur because the pointers are + * overwritten with NULL. */ + + Common->nrow = 0 ; + Common->mark = EMPTY ; + Common->xworksize = 0 ; + Common->iworksize = 0 ; + Common->Flag = NULL ; + Common->Head = NULL ; + Common->Iwork = NULL ; + Common->Xwork = NULL ; + Common->no_workspace_reallocate = FALSE ; + + /* ---------------------------------------------------------------------- */ + /* statistics */ + /* ---------------------------------------------------------------------- */ + + /* fl and lnz are computed in cholmod_analyze and cholmod_rowcolcounts */ + Common->fl = EMPTY ; + Common->lnz = EMPTY ; + + /* modfl is computed in cholmod_updown, cholmod_rowadd, and cholmod_rowdel*/ + Common->modfl = EMPTY ; + + /* all routines use status as their error-report code */ + Common->status = CHOLMOD_OK ; + + Common->malloc_count = 0 ; /* # calls to malloc minus # calls to free */ + Common->memory_usage = 0 ; /* peak memory usage (in bytes) */ + Common->memory_inuse = 0 ; /* current memory in use (in bytes) */ + + Common->nrealloc_col = 0 ; + Common->nrealloc_factor = 0 ; + Common->ndbounds_hit = 0 ; + Common->rowfacfl = 0 ; + Common->aatfl = EMPTY ; + + /* Common->called_nd is TRUE if cholmod_analyze called or NESDIS */ + Common->called_nd = FALSE ; + + Common->blas_ok = TRUE ; /* false if BLAS int overflow occurs */ + + /* ---------------------------------------------------------------------- */ + /* default SuiteSparseQR knobs and statististics */ + /* ---------------------------------------------------------------------- */ + + for (k = 0 ; k < 4 ; k++) Common->SPQR_xstat [k] = 0 ; + for (k = 0 ; k < 10 ; k++) Common->SPQR_istat [k] = 0 ; + Common->SPQR_grain = 1 ; /* no Intel TBB multitasking, by default */ + Common->SPQR_small = 1e6 ; /* target min task size for TBB */ + Common->SPQR_shrink = 1 ; /* controls SPQR shrink realloc */ + Common->SPQR_nthreads = 0 ; /* 0: let TBB decide how many threads to use */ + + DEBUG_INIT ("cholmod start", Common) ; + return (TRUE) ; +} + + +/* ========================================================================== */ +/* === cholmod_defaults ===================================================== */ +/* ========================================================================== */ + +/* Set Common default parameters, except for the function pointers. + * + * workspace: none + */ + +int CHOLMOD(defaults) +( + cholmod_common *Common +) +{ + Int i ; + + RETURN_IF_NULL_COMMON (FALSE) ; + + /* ---------------------------------------------------------------------- */ + /* default control parameters */ + /* ---------------------------------------------------------------------- */ + + Common->dbound = 0.0 ; + Common->grow0 = 1.2 ; + Common->grow1 = 1.2 ; + Common->grow2 = 5 ; + Common->maxrank = 8 ; + + Common->final_asis = TRUE ; + Common->final_super = TRUE ; + Common->final_ll = FALSE ; + Common->final_pack = TRUE ; + Common->final_monotonic = TRUE ; + Common->final_resymbol = FALSE ; + + /* use simplicial factorization if flop/nnz(L) < 40, supernodal otherwise */ + Common->supernodal = CHOLMOD_AUTO ; + Common->supernodal_switch = 40 ; + + Common->nrelax [0] = 4 ; + Common->nrelax [1] = 16 ; + Common->nrelax [2] = 48 ; + Common->zrelax [0] = 0.8 ; + Common->zrelax [1] = 0.1 ; + Common->zrelax [2] = 0.05 ; + + Common->prefer_zomplex = FALSE ; + Common->prefer_upper = TRUE ; + Common->prefer_binary = FALSE ; + Common->quick_return_if_not_posdef = FALSE ; + + /* METIS workarounds */ + Common->metis_memory = 0.0 ; /* > 0 for memory guard (2 is reasonable) */ + Common->metis_nswitch = 3000 ; + Common->metis_dswitch = 0.66 ; + + Common->print = 3 ; + Common->precise = FALSE ; + + /* ---------------------------------------------------------------------- */ + /* default ordering methods */ + /* ---------------------------------------------------------------------- */ + + /* Note that if the Partition module is not installed, the CHOLMOD_METIS + * and CHOLMOD_NESDIS methods will not be available. cholmod_analyze will + * report the CHOLMOD_NOT_INSTALLED error, and safely skip over them. + */ + +#if (CHOLMOD_MAXMETHODS < 9) +#error "CHOLMOD_MAXMETHODS must be 9 or more (defined in cholmod_core.h)." +#endif + + /* default strategy: try given, AMD, and then METIS if AMD reports high + * fill-in. NESDIS can be used instead, if Common->default_nesdis is TRUE. + */ + Common->nmethods = 0 ; /* use default strategy */ + Common->default_nesdis = FALSE ; /* use METIS in default strategy */ + + Common->current = 0 ; /* current method being tried */ + Common->selected = 0 ; /* the best method selected */ + + /* first, fill each method with default parameters */ + for (i = 0 ; i <= CHOLMOD_MAXMETHODS ; i++) + { + /* CHOLMOD's default method is AMD for A or AA' */ + Common->method [i].ordering = CHOLMOD_AMD ; + + /* CHOLMOD nested dissection and minimum degree parameter */ + Common->method [i].prune_dense = 10.0 ; /* dense row/col control */ + + /* min degree parameters (AMD, COLAMD, SYMAMD, CAMD, CCOLAMD, CSYMAMD)*/ + Common->method [i].prune_dense2 = -1 ; /* COLAMD dense row control */ + Common->method [i].aggressive = TRUE ; /* aggressive absorption */ + Common->method [i].order_for_lu = FALSE ;/* order for Cholesky not LU */ + + /* CHOLMOD's nested dissection (METIS + constrained AMD) */ + Common->method [i].nd_small = 200 ; /* small graphs aren't cut */ + Common->method [i].nd_compress = TRUE ; /* compress graph & subgraphs */ + Common->method [i].nd_camd = 1 ; /* use CAMD */ + Common->method [i].nd_components = FALSE ; /* lump connected comp. */ + Common->method [i].nd_oksep = 1.0 ; /* sep ok if < oksep*n */ + + /* statistics for each method are not yet computed */ + Common->method [i].fl = EMPTY ; + Common->method [i].lnz = EMPTY ; + } + + Common->postorder = TRUE ; /* follow ordering with weighted postorder */ + + /* Next, define some methods. The first five use default parameters. */ + Common->method [0].ordering = CHOLMOD_GIVEN ; /* skip if UserPerm NULL */ + Common->method [1].ordering = CHOLMOD_AMD ; + Common->method [2].ordering = CHOLMOD_METIS ; + Common->method [3].ordering = CHOLMOD_NESDIS ; + Common->method [4].ordering = CHOLMOD_NATURAL ; + + /* CHOLMOD's nested dissection with large leaves of separator tree */ + Common->method [5].ordering = CHOLMOD_NESDIS ; + Common->method [5].nd_small = 20000 ; + + /* CHOLMOD's nested dissection with tiny leaves, and no AMD ordering */ + Common->method [6].ordering = CHOLMOD_NESDIS ; + Common->method [6].nd_small = 4 ; + Common->method [6].nd_camd = 0 ; /* no CSYMAMD or CAMD */ + + /* CHOLMOD's nested dissection with no dense node removal */ + Common->method [7].ordering = CHOLMOD_NESDIS ; + Common->method [7].prune_dense = -1. ; + + /* COLAMD for A*A', AMD for A */ + Common->method [8].ordering = CHOLMOD_COLAMD ; + + return (TRUE) ; +} + + +/* ========================================================================== */ +/* === cholmod_finish ======================================================= */ +/* ========================================================================== */ + +/* The last call to CHOLMOD must be cholmod_finish. You may call this routine + * more than once, and can safely call any other CHOLMOD routine after calling + * it (including cholmod_start). + * + * The statistics and parameter settings in Common are preserved. The + * workspace in Common is freed. This routine is just another name for + * cholmod_free_work. + */ + +int CHOLMOD(finish) +( + cholmod_common *Common +) +{ + return (CHOLMOD(free_work) (Common)) ; +} + + +/* ========================================================================== */ +/* === cholmod_allocate_work ================================================ */ +/* ========================================================================== */ + +/* Allocate and initialize workspace for CHOLMOD routines, or increase the size + * of already-allocated workspace. If enough workspace is already allocated, + * then nothing happens. + * + * workspace: Flag (nrow), Head (nrow+1), Iwork (iworksize), Xwork (xworksize) + */ + +int CHOLMOD(allocate_work) +( + /* ---- input ---- */ + size_t nrow, /* # of rows in the matrix A */ + size_t iworksize, /* size of Iwork */ + size_t xworksize, /* size of Xwork */ + /* --------------- */ + cholmod_common *Common +) +{ + double *W ; + Int *Head ; + Int i ; + size_t nrow1 ; + int ok = TRUE ; + + /* ---------------------------------------------------------------------- */ + /* get inputs */ + /* ---------------------------------------------------------------------- */ + + RETURN_IF_NULL_COMMON (FALSE) ; + Common->status = CHOLMOD_OK ; + + /* ---------------------------------------------------------------------- */ + /* Allocate Flag (nrow) and Head (nrow+1) */ + /* ---------------------------------------------------------------------- */ + + nrow = MAX (1, nrow) ; + + /* nrow1 = nrow + 1 */ + nrow1 = CHOLMOD(add_size_t) (nrow, 1, &ok) ; + if (!ok) + { + /* nrow+1 causes size_t overflow ; problem is too large */ + Common->status = CHOLMOD_TOO_LARGE ; + CHOLMOD(free_work) (Common) ; + return (FALSE) ; + } + + if (nrow > Common->nrow) + { + + if (Common->no_workspace_reallocate) + { + /* CHOLMOD is not allowed to change the workspace here */ + Common->status = CHOLMOD_INVALID ; + return (FALSE) ; + } + + /* free the old workspace (if any) and allocate new space */ + Common->Flag = CHOLMOD(free) (Common->nrow, sizeof (Int), Common->Flag, + Common) ; + Common->Head = CHOLMOD(free) (Common->nrow+1,sizeof (Int), Common->Head, + Common) ; + Common->Flag = CHOLMOD(malloc) (nrow, sizeof (Int), Common) ; + Common->Head = CHOLMOD(malloc) (nrow1, sizeof (Int), Common) ; + + /* record the new size of Flag and Head */ + Common->nrow = nrow ; + + if (Common->status < CHOLMOD_OK) + { + CHOLMOD(free_work) (Common) ; + return (FALSE) ; + } + + /* initialize Flag and Head */ + Common->mark = EMPTY ; + CHOLMOD(clear_flag) (Common) ; + Head = Common->Head ; + for (i = 0 ; i <= (Int) (nrow) ; i++) + { + Head [i] = EMPTY ; + } + } + + /* ---------------------------------------------------------------------- */ + /* Allocate Iwork (iworksize) */ + /* ---------------------------------------------------------------------- */ + + iworksize = MAX (1, iworksize) ; + if (iworksize > Common->iworksize) + { + + if (Common->no_workspace_reallocate) + { + /* CHOLMOD is not allowed to change the workspace here */ + Common->status = CHOLMOD_INVALID ; + return (FALSE) ; + } + + /* free the old workspace (if any) and allocate new space. + * integer overflow safely detected in cholmod_malloc */ + CHOLMOD(free) (Common->iworksize, sizeof (Int), Common->Iwork, Common) ; + Common->Iwork = CHOLMOD(malloc) (iworksize, sizeof (Int), Common) ; + + /* record the new size of Iwork */ + Common->iworksize = iworksize ; + + if (Common->status < CHOLMOD_OK) + { + CHOLMOD(free_work) (Common) ; + return (FALSE) ; + } + + /* note that Iwork does not need to be initialized */ + } + + /* ---------------------------------------------------------------------- */ + /* Allocate Xwork (xworksize) and set it to ((double) 0.) */ + /* ---------------------------------------------------------------------- */ + + /* make sure xworksize is >= 1 */ + xworksize = MAX (1, xworksize) ; + if (xworksize > Common->xworksize) + { + + if (Common->no_workspace_reallocate) + { + /* CHOLMOD is not allowed to change the workspace here */ + Common->status = CHOLMOD_INVALID ; + return (FALSE) ; + } + + /* free the old workspace (if any) and allocate new space */ + CHOLMOD(free) (Common->xworksize, sizeof (double), Common->Xwork, + Common) ; + Common->Xwork = CHOLMOD(malloc) (xworksize, sizeof (double), Common) ; + + /* record the new size of Xwork */ + Common->xworksize = xworksize ; + + if (Common->status < CHOLMOD_OK) + { + CHOLMOD(free_work) (Common) ; + return (FALSE) ; + } + + /* initialize Xwork */ + W = Common->Xwork ; + for (i = 0 ; i < (Int) xworksize ; i++) + { + W [i] = 0. ; + } + } + + return (TRUE) ; +} + + +/* ========================================================================== */ +/* === cholmod_free_work ==================================================== */ +/* ========================================================================== */ + +/* Deallocate the CHOLMOD workspace. + * + * workspace: deallocates all workspace in Common + */ + +int CHOLMOD(free_work) +( + cholmod_common *Common +) +{ + RETURN_IF_NULL_COMMON (FALSE) ; + Common->Flag = CHOLMOD(free) (Common->nrow, sizeof (Int), + Common->Flag, Common) ; + Common->Head = CHOLMOD(free) (Common->nrow+1, sizeof (Int), + Common->Head, Common) ; + Common->Iwork = CHOLMOD(free) (Common->iworksize, sizeof (Int), + Common->Iwork, Common) ; + Common->Xwork = CHOLMOD(free) (Common->xworksize, sizeof (double), + Common->Xwork, Common) ; + Common->nrow = 0 ; + Common->iworksize = 0 ; + Common->xworksize = 0 ; + return (TRUE) ; +} + + +/* ========================================================================== */ +/* === cholmod_clear_flag =================================================== */ +/* ========================================================================== */ + +/* Increment mark to ensure Flag [0..nrow-1] < mark. If integer overflow + * occurs, or mark was initially negative, reset the entire array. This is + * not an error condition, but an intended function of the Flag workspace. + * + * workspace: Flag (nrow). Does not modify Flag if nrow is zero. + */ + +UF_long cholmod_l_clear_flag +( + cholmod_common *Common +) +{ + Int i, nrow, *Flag ; + + RETURN_IF_NULL_COMMON (-1) ; + + Common->mark++ ; + if (Common->mark <= 0) + { + nrow = Common->nrow ; + Flag = Common->Flag ; + PRINT2 (("reset Flag: nrow "ID"\n", nrow)) ; + PRINT2 (("reset Flag: mark %ld\n", Common->mark)) ; + for (i = 0 ; i < nrow ; i++) + { + Flag [i] = EMPTY ; + } + Common->mark = 0 ; + } + return (Common->mark) ; +} + + +/* ========================================================================== */ +/* ==== cholmod_maxrank ===================================================== */ +/* ========================================================================== */ + +/* Find a valid value of Common->maxrank. Returns 0 if error, or 2, 4, or 8 + * if successful. */ + +size_t cholmod_l_maxrank /* returns validated value of Common->maxrank */ +( + /* ---- input ---- */ + size_t n, /* A and L will have n rows */ + /* --------------- */ + cholmod_common *Common +) +{ + size_t maxrank ; + RETURN_IF_NULL_COMMON (0) ; + maxrank = Common->maxrank ; + if (n > 0) + { + /* Ensure maxrank*n*sizeof(double) does not result in integer overflow. + * If n is so large that 2*n*sizeof(double) results in integer overflow + * (n = 268,435,455 if an Int is 32 bits), then maxrank will be 0 or 1, + * but maxrank will be set to 2 below. 2*n will not result in integer + * overflow, and CHOLMOD will run out of memory or safely detect integer + * overflow elsewhere. + */ + maxrank = MIN (maxrank, Size_max / (n * sizeof (double))) ; + } + if (maxrank <= 2) + { + maxrank = 2 ; + } + else if (maxrank <= 4) + { + maxrank = 4 ; + } + else + { + maxrank = 8 ; + } + return (maxrank) ; +} + + +/* ========================================================================== */ +/* === cholmod_dbound ======================================================= */ +/* ========================================================================== */ + +/* Ensure the absolute value of a diagonal entry, D (j,j), is greater than + * Common->dbound. This routine is not meant for the user to call. It is used + * by the various LDL' factorization and update/downdate routines. The + * default value of Common->dbound is zero, and in that case this routine is not + * called at all. No change is made if D (j,j) is NaN. CHOLMOD does not call + * this routine if Common->dbound is NaN. + */ + +double cholmod_l_dbound /* returns modified diagonal entry of D */ +( + /* ---- input ---- */ + double dj, /* diagonal entry of D, for LDL' factorization */ + /* --------------- */ + cholmod_common *Common +) +{ + double dbound ; + RETURN_IF_NULL_COMMON (0) ; + if (!IS_NAN (dj)) + { + dbound = Common->dbound ; + if (dj < 0) + { + if (dj > -dbound) + { + dj = -dbound ; + Common->ndbounds_hit++ ; + if (Common->status == CHOLMOD_OK) + { + ERROR (CHOLMOD_DSMALL, "diagonal below threshold") ; + } + } + } + else + { + if (dj < dbound) + { + dj = dbound ; + Common->ndbounds_hit++ ; + if (Common->status == CHOLMOD_OK) + { + ERROR (CHOLMOD_DSMALL, "diagonal below threshold") ; + } + } + } + } + return (dj) ; +} diff --git a/spqr_mini/cholmod_common.h b/spqr_mini/cholmod_common.h new file mode 100644 index 000000000..e69de29bb diff --git a/spqr_mini/cholmod_core.h b/spqr_mini/cholmod_core.h new file mode 100644 index 000000000..1637b8267 --- /dev/null +++ b/spqr_mini/cholmod_core.h @@ -0,0 +1,2290 @@ +/* ========================================================================== */ +/* === Include/cholmod_core.h =============================================== */ +/* ========================================================================== */ + +/* ----------------------------------------------------------------------------- + * CHOLMOD/Include/cholmod_core.h. + * Copyright (C) 2005-2006, Univ. of Florida. Author: Timothy A. Davis + * CHOLMOD/Include/cholmod_core.h is licensed under Version 2.1 of the GNU + * Lesser General Public License. See lesser.txt for a text of the license. + * CHOLMOD is also available under other licenses; contact authors for details. + * http://www.cise.ufl.edu/research/sparse + * -------------------------------------------------------------------------- */ + +/* CHOLMOD Core module: basic CHOLMOD objects and routines. + * Required by all CHOLMOD modules. Requires no other module or package. + * + * The CHOLMOD modules are: + * + * Core basic data structures and definitions + * Check check/print the 5 CHOLMOD objects, & 3 types of integer vectors + * Cholesky sparse Cholesky factorization + * Modify sparse Cholesky update/downdate/row-add/row-delete + * MatrixOps sparse matrix functions (add, multiply, norm, ...) + * Supernodal supernodal sparse Cholesky factorization + * Partition graph-partitioning based orderings + * + * The CHOLMOD objects: + * -------------------- + * + * cholmod_common parameters, statistics, and workspace + * cholmod_sparse a sparse matrix in compressed column form + * cholmod_factor an LL' or LDL' factorization + * cholmod_dense a dense matrix + * cholmod_triplet a sparse matrix in "triplet" form + * + * The Core module described here defines the CHOLMOD data structures, and + * basic operations on them. To create and solve a sparse linear system Ax=b, + * the user must create A and b, populate them with values, and then pass them + * to the routines in the CHOLMOD Cholesky module. There are two primary + * methods for creating A: (1) allocate space for a column-oriented sparse + * matrix and fill it with pattern and values, or (2) create a triplet form + * matrix and convert it to a sparse matrix. The latter option is simpler. + * + * The matrices b and x are typically dense matrices, but can also be sparse. + * You can allocate and free them as dense matrices with the + * cholmod_allocate_dense and cholmod_free_dense routines. + * + * The cholmod_factor object contains the symbolic and numeric LL' or LDL' + * factorization of sparse symmetric matrix. The matrix must be positive + * definite for an LL' factorization. It need only be symmetric and have well- + * conditioned leading submatrices for it to have an LDL' factorization + * (CHOLMOD does not pivot for numerical stability). It is typically created + * with the cholmod_factorize routine in the Cholesky module, but can also + * be initialized to L=D=I in the Core module and then modified by the Modify + * module. It must be freed with cholmod_free_factor, defined below. + * + * The Core routines for each object are described below. Each list is split + * into two parts: the primary routines and secondary routines. + * + * ============================================================================ + * === cholmod_common ========================================================= + * ============================================================================ + * + * The Common object contains control parameters, statistics, and + * You must call cholmod_start before calling any other CHOLMOD routine, and + * must call cholmod_finish as your last call to CHOLMOD, with two exceptions: + * you may call cholmod_print_common and cholmod_check_common in the Check + * module after calling cholmod_finish. + * + * cholmod_start first call to CHOLMOD + * cholmod_finish last call to CHOLMOD + * ----------------------------- + * cholmod_defaults restore default parameters + * cholmod_maxrank maximum rank for update/downdate + * cholmod_allocate_work allocate workspace in Common + * cholmod_free_work free workspace in Common + * cholmod_clear_flag clear Flag workspace in Common + * cholmod_error called when CHOLMOD encounters an error + * cholmod_dbound for internal use in CHOLMOD only + * cholmod_hypot compute sqrt (x*x + y*y) accurately + * cholmod_divcomplex complex division, c = a/b + * + * ============================================================================ + * === cholmod_sparse ========================================================= + * ============================================================================ + * + * A sparse matrix is held in compressed column form. In the basic type + * ("packed", which corresponds to a MATLAB sparse matrix), an n-by-n matrix + * with nz entries is held in three arrays: p of size n+1, i of size nz, and x + * of size nz. Row indices of column j are held in i [p [j] ... p [j+1]-1] and + * in the same locations in x. There may be no duplicate entries in a column. + * Row indices in each column may be sorted or unsorted (CHOLMOD keeps track). + * A->stype determines the storage mode: 0 if both upper/lower parts are stored, + * -1 if A is symmetric and just tril(A) is stored, +1 if symmetric and triu(A) + * is stored. + * + * cholmod_allocate_sparse allocate a sparse matrix + * cholmod_free_sparse free a sparse matrix + * ----------------------------- + * cholmod_reallocate_sparse change the size (# entries) of sparse matrix + * cholmod_nnz number of nonzeros in a sparse matrix + * cholmod_speye sparse identity matrix + * cholmod_spzeros sparse zero matrix + * cholmod_transpose transpose a sparse matrix + * cholmod_ptranspose transpose/permute a sparse matrix + * cholmod_transpose_unsym transpose/permute an unsymmetric sparse matrix + * cholmod_transpose_sym transpose/permute a symmetric sparse matrix + * cholmod_sort sort row indices in each column of sparse matrix + * cholmod_band C = tril (triu (A,k1), k2) + * cholmod_band_inplace A = tril (triu (A,k1), k2) + * cholmod_aat C = A*A' + * cholmod_copy_sparse C = A, create an exact copy of a sparse matrix + * cholmod_copy C = A, with possible change of stype + * cholmod_add C = alpha*A + beta*B + * cholmod_sparse_xtype change the xtype of a sparse matrix + * + * ============================================================================ + * === cholmod_factor ========================================================= + * ============================================================================ + * + * The data structure for an LL' or LDL' factorization is too complex to + * describe in one sentence. This object can hold the symbolic analysis alone, + * or in combination with a "simplicial" (similar to a sparse matrix) or + * "supernodal" form of the numerical factorization. Only the routine to free + * a factor is primary, since a factor object is created by the factorization + * routine (cholmod_factorize). It must be freed with cholmod_free_factor. + * + * cholmod_free_factor free a factor + * ----------------------------- + * cholmod_allocate_factor allocate a factor (LL' or LDL') + * cholmod_reallocate_factor change the # entries in a factor + * cholmod_change_factor change the type of factor (e.g., LDL' to LL') + * cholmod_pack_factor pack the columns of a factor + * cholmod_reallocate_column resize a single column of a factor + * cholmod_factor_to_sparse create a sparse matrix copy of a factor + * cholmod_copy_factor create a copy of a factor + * cholmod_factor_xtype change the xtype of a factor + * + * Note that there is no cholmod_sparse_to_factor routine to create a factor + * as a copy of a sparse matrix. It could be done, after a fashion, but a + * lower triangular sparse matrix would not necessarily have a chordal graph, + * which would break the many CHOLMOD routines that rely on this property. + * + * ============================================================================ + * === cholmod_dense ========================================================== + * ============================================================================ + * + * The solve routines and some of the MatrixOps and Modify routines use dense + * matrices as inputs. These are held in column-major order. With a leading + * dimension of d, the entry in row i and column j is held in x [i+j*d]. + * + * cholmod_allocate_dense allocate a dense matrix + * cholmod_free_dense free a dense matrix + * ----------------------------- + * cholmod_zeros allocate a dense matrix of all zeros + * cholmod_ones allocate a dense matrix of all ones + * cholmod_eye allocate a dense identity matrix + * cholmod_sparse_to_dense create a dense matrix copy of a sparse matrix + * cholmod_dense_to_sparse create a sparse matrix copy of a dense matrix + * cholmod_copy_dense create a copy of a dense matrix + * cholmod_copy_dense2 copy a dense matrix (pre-allocated) + * cholmod_dense_xtype change the xtype of a dense matrix + * + * ============================================================================ + * === cholmod_triplet ======================================================== + * ============================================================================ + * + * A sparse matrix held in triplet form is the simplest one for a user to + * create. It consists of a list of nz entries in arbitrary order, held in + * three arrays: i, j, and x, each of length nk. The kth entry is in row i[k], + * column j[k], with value x[k]. There may be duplicate values; if A(i,j) + * appears more than once, its value is the sum of the entries with those row + * and column indices. + * + * cholmod_allocate_triplet allocate a triplet matrix + * cholmod_triplet_to_sparse create a sparse matrix copy of a triplet matrix + * cholmod_free_triplet free a triplet matrix + * ----------------------------- + * cholmod_reallocate_triplet change the # of entries in a triplet matrix + * cholmod_sparse_to_triplet create a triplet matrix copy of a sparse matrix + * cholmod_copy_triplet create a copy of a triplet matrix + * cholmod_triplet_xtype change the xtype of a triplet matrix + * + * ============================================================================ + * === memory management ====================================================== + * ============================================================================ + * + * cholmod_malloc malloc wrapper + * cholmod_calloc calloc wrapper + * cholmod_free free wrapper + * cholmod_realloc realloc wrapper + * cholmod_realloc_multiple realloc wrapper for multiple objects + * + * ============================================================================ + * === Core CHOLMOD prototypes ================================================ + * ============================================================================ + * + * All CHOLMOD routines (in all modules) use the following protocol for return + * values, with one exception: + * + * int TRUE (1) if successful, or FALSE (0) otherwise. + * (exception: cholmod_divcomplex) + * UF_long a value >= 0 if successful, or -1 otherwise. + * double a value >= 0 if successful, or -1 otherwise. + * size_t a value > 0 if successful, or 0 otherwise. + * void * a non-NULL pointer to newly allocated memory if + * successful, or NULL otherwise. + * cholmod_sparse * a non-NULL pointer to a newly allocated matrix + * if successful, or NULL otherwise. + * cholmod_factor * a non-NULL pointer to a newly allocated factor + * if successful, or NULL otherwise. + * cholmod_triplet * a non-NULL pointer to a newly allocated triplet + * matrix if successful, or NULL otherwise. + * cholmod_dense * a non-NULL pointer to a newly allocated triplet + * matrix if successful, or NULL otherwise. + * + * The last parameter to all routines is always a pointer to the CHOLMOD + * Common object. + * + * TRUE and FALSE are not defined here, since they may conflict with the user + * program. A routine that described here returning TRUE or FALSE returns 1 + * or 0, respectively. Any TRUE/FALSE parameter is true if nonzero, false if + * zero. + */ + +#ifndef CHOLMOD_CORE_H +#define CHOLMOD_CORE_H + +/* ========================================================================== */ +/* === CHOLMOD version ====================================================== */ +/* ========================================================================== */ + +/* All versions of CHOLMOD will include the following definitions. + * As an example, to test if the version you are using is 1.3 or later: + * + * if (CHOLMOD_VERSION >= CHOLMOD_VER_CODE (1,3)) ... + * + * This also works during compile-time: + * + * #if CHOLMOD_VERSION >= CHOLMOD_VER_CODE (1,3) + * printf ("This is version 1.3 or later\n") ; + * #else + * printf ("This is version is earlier than 1.3\n") ; + * #endif + */ + +#define CHOLMOD_DATE "Nov 30, 2009" +#define CHOLMOD_VER_CODE(main,sub) ((main) * 1000 + (sub)) +#define CHOLMOD_MAIN_VERSION 1 +#define CHOLMOD_SUB_VERSION 7 +#define CHOLMOD_SUBSUB_VERSION 2 +#define CHOLMOD_VERSION \ + CHOLMOD_VER_CODE(CHOLMOD_MAIN_VERSION,CHOLMOD_SUB_VERSION) + + +/* ========================================================================== */ +/* === non-CHOLMOD include files ============================================ */ +/* ========================================================================== */ + +/* This is the only non-CHOLMOD include file imposed on the user program. + * It required for size_t definition used here. CHOLMOD itself includes other + * ANSI C89 standard #include files, but does not expose them to the user. + * + * CHOLMOD assumes that your C compiler is ANSI C89 compliant. It does not make + * use of ANSI C99 features. + */ + +#include +#include + +/* ========================================================================== */ +/* === CHOLMOD objects ====================================================== */ +/* ========================================================================== */ + +/* Each CHOLMOD object has its own type code. */ + +#define CHOLMOD_COMMON 0 +#define CHOLMOD_SPARSE 1 +#define CHOLMOD_FACTOR 2 +#define CHOLMOD_DENSE 3 +#define CHOLMOD_TRIPLET 4 + +/* ========================================================================== */ +/* === CHOLMOD Common ======================================================= */ +/* ========================================================================== */ + +/* itype defines the types of integer used: */ +#define CHOLMOD_INT 0 /* all integer arrays are int */ +#define CHOLMOD_INTLONG 1 /* most are int, some are UF_long */ +#define CHOLMOD_LONG 2 /* all integer arrays are UF_long */ + +/* The itype of all parameters for all CHOLMOD routines must match. + * FUTURE WORK: CHOLMOD_INTLONG is not yet supported. + */ + +/* dtype defines what the numerical type is (double or float): */ +#define CHOLMOD_DOUBLE 0 /* all numerical values are double */ +#define CHOLMOD_SINGLE 1 /* all numerical values are float */ + +/* The dtype of all parameters for all CHOLMOD routines must match. + * + * Scalar floating-point values are always passed as double arrays of size 2 + * (for the real and imaginary parts). They are typecast to float as needed. + * FUTURE WORK: the float case is not supported yet. + */ + +/* xtype defines the kind of numerical values used: */ +#define CHOLMOD_PATTERN 0 /* pattern only, no numerical values */ +#define CHOLMOD_REAL 1 /* a real matrix */ +#define CHOLMOD_COMPLEX 2 /* a complex matrix (ANSI C99 compatible) */ +#define CHOLMOD_ZOMPLEX 3 /* a complex matrix (MATLAB compatible) */ + +/* The xtype of all parameters for all CHOLMOD routines must match. + * + * CHOLMOD_PATTERN: x and z are ignored. + * CHOLMOD_DOUBLE: x is non-null of size nzmax, z is ignored. + * CHOLMOD_COMPLEX: x is non-null of size 2*nzmax doubles, z is ignored. + * CHOLMOD_ZOMPLEX: x and z are non-null of size nzmax + * + * In the real case, z is ignored. The kth entry in the matrix is x [k]. + * There are two methods for the complex case. In the ANSI C99-compatible + * CHOLMOD_COMPLEX case, the real and imaginary parts of the kth entry + * are in x [2*k] and x [2*k+1], respectively. z is ignored. In the + * MATLAB-compatible CHOLMOD_ZOMPLEX case, the real and imaginary + * parts of the kth entry are in x [k] and z [k]. + * + * Scalar floating-point values are always passed as double arrays of size 2 + * (real and imaginary parts). The imaginary part of a scalar is ignored if + * the routine operates on a real matrix. + * + * These Modules support complex and zomplex matrices, with a few exceptions: + * + * Check all routines + * Cholesky all routines + * Core all except cholmod_aat, add, band, copy + * Demo all routines + * Partition all routines + * Supernodal all routines support any real, complex, or zomplex input. + * There will never be a supernodal zomplex L; a complex + * supernodal L is created if A is zomplex. + * Tcov all routines + * Valgrind all routines + * + * These Modules provide partial support for complex and zomplex matrices: + * + * MATLAB all routines support real and zomplex only, not complex, + * with the exception of ldlupdate, which supports + * real matrices only. This is a minor constraint since + * MATLAB's matrices are all real or zomplex. + * MatrixOps only norm_dense, norm_sparse, and sdmult support complex + * and zomplex + * + * These Modules do not support complex and zomplex matrices at all: + * + * Modify all routines support real matrices only + */ + +/* Definitions for cholmod_common: */ +#define CHOLMOD_MAXMETHODS 9 /* maximum number of different methods that */ + /* cholmod_analyze can try. Must be >= 9. */ + +/* Common->status values. zero means success, negative means a fatal error, + * positive is a warning. */ +#define CHOLMOD_OK 0 /* success */ +#define CHOLMOD_NOT_INSTALLED (-1) /* failure: method not installed */ +#define CHOLMOD_OUT_OF_MEMORY (-2) /* failure: out of memory */ +#define CHOLMOD_TOO_LARGE (-3) /* failure: integer overflow occured */ +#define CHOLMOD_INVALID (-4) /* failure: invalid input */ +#define CHOLMOD_NOT_POSDEF (1) /* warning: matrix not pos. def. */ +#define CHOLMOD_DSMALL (2) /* warning: D for LDL' or diag(L) or */ + /* LL' has tiny absolute value */ + +/* ordering method (also used for L->ordering) */ +#define CHOLMOD_NATURAL 0 /* use natural ordering */ +#define CHOLMOD_GIVEN 1 /* use given permutation */ +#define CHOLMOD_AMD 2 /* use minimum degree (AMD) */ +#define CHOLMOD_METIS 3 /* use METIS' nested dissection */ +#define CHOLMOD_NESDIS 4 /* use CHOLMOD's version of nested dissection:*/ + /* node bisector applied recursively, followed + * by constrained minimum degree (CSYMAMD or + * CCOLAMD) */ +#define CHOLMOD_COLAMD 5 /* use AMD for A, COLAMD for A*A' */ + +/* POSTORDERED is not a method, but a result of natural ordering followed by a + * weighted postorder. It is used for L->ordering, not method [ ].ordering. */ +#define CHOLMOD_POSTORDERED 6 /* natural ordering, postordered. */ + +/* supernodal strategy (for Common->supernodal) */ +#define CHOLMOD_SIMPLICIAL 0 /* always do simplicial */ +#define CHOLMOD_AUTO 1 /* select simpl/super depending on matrix */ +#define CHOLMOD_SUPERNODAL 2 /* always do supernodal */ + +typedef struct cholmod_common_struct +{ + /* ---------------------------------------------------------------------- */ + /* parameters for symbolic/numeric factorization and update/downdate */ + /* ---------------------------------------------------------------------- */ + + double dbound ; /* Smallest absolute value of diagonal entries of D + * for LDL' factorization and update/downdate/rowadd/ + * rowdel, or the diagonal of L for an LL' factorization. + * Entries in the range 0 to dbound are replaced with dbound. + * Entries in the range -dbound to 0 are replaced with -dbound. No + * changes are made to the diagonal if dbound <= 0. Default: zero */ + + double grow0 ; /* For a simplicial factorization, L->i and L->x can + * grow if necessary. grow0 is the factor by which + * it grows. For the initial space, L is of size MAX (1,grow0) times + * the required space. If L runs out of space, the new size of L is + * MAX(1.2,grow0) times the new required space. If you do not plan on + * modifying the LDL' factorization in the Modify module, set grow0 to + * zero (or set grow2 to 0, see below). Default: 1.2 */ + + double grow1 ; + + size_t grow2 ; /* For a simplicial factorization, each column j of L + * is initialized with space equal to + * grow1*L->ColCount[j] + grow2. If grow0 < 1, grow1 < 1, or grow2 == 0, + * then the space allocated is exactly equal to L->ColCount[j]. If the + * column j runs out of space, it increases to grow1*need + grow2 in + * size, where need is the total # of nonzeros in that column. If you do + * not plan on modifying the factorization in the Modify module, set + * grow2 to zero. Default: grow1 = 1.2, grow2 = 5. */ + + size_t maxrank ; /* rank of maximum update/downdate. Valid values: + * 2, 4, or 8. A value < 2 is set to 2, and a + * value > 8 is set to 8. It is then rounded up to the next highest + * power of 2, if not already a power of 2. Workspace (Xwork, below) of + * size nrow-by-maxrank double's is allocated for the update/downdate. + * If an update/downdate of rank-k is requested, with k > maxrank, + * it is done in steps of maxrank. Default: 8, which is fastest. + * Memory usage can be reduced by setting maxrank to 2 or 4. + */ + + double supernodal_switch ; /* supernodal vs simplicial factorization */ + int supernodal ; /* If Common->supernodal <= CHOLMOD_SIMPLICIAL + * (0) then cholmod_analyze performs a + * simplicial analysis. If >= CHOLMOD_SUPERNODAL (2), then a supernodal + * analysis is performed. If == CHOLMOD_AUTO (1) and + * flop/nnz(L) < Common->supernodal_switch, then a simplicial analysis + * is done. A supernodal analysis done otherwise. + * Default: CHOLMOD_AUTO. Default supernodal_switch = 40 */ + + int final_asis ; /* If TRUE, then ignore the other final_* parameters + * (except for final_pack). + * The factor is left as-is when done. Default: TRUE.*/ + + int final_super ; /* If TRUE, leave a factor in supernodal form when + * supernodal factorization is finished. If FALSE, + * then convert to a simplicial factor when done. + * Default: TRUE */ + + int final_ll ; /* If TRUE, leave factor in LL' form when done. + * Otherwise, leave in LDL' form. Default: FALSE */ + + int final_pack ; /* If TRUE, pack the columns when done. If TRUE, and + * cholmod_factorize is called with a symbolic L, L is + * allocated with exactly the space required, using L->ColCount. If you + * plan on modifying the factorization, set Common->final_pack to FALSE, + * and each column will be given a little extra slack space for future + * growth in fill-in due to updates. Default: TRUE */ + + int final_monotonic ; /* If TRUE, ensure columns are monotonic when done. + * Default: TRUE */ + + int final_resymbol ;/* if cholmod_factorize performed a supernodal + * factorization, final_resymbol is true, and + * final_super is FALSE (convert a simplicial numeric factorization), + * then numerically zero entries that resulted from relaxed supernodal + * amalgamation are removed. This does not remove entries that are zero + * due to exact numeric cancellation, since doing so would break the + * update/downdate rowadd/rowdel routines. Default: FALSE. */ + + /* supernodal relaxed amalgamation parameters: */ + double zrelax [3] ; + size_t nrelax [3] ; + + /* Let ns be the total number of columns in two adjacent supernodes. + * Let z be the fraction of zero entries in the two supernodes if they + * are merged (z includes zero entries from prior amalgamations). The + * two supernodes are merged if: + * (ns <= nrelax [0]) || (no new zero entries added) || + * (ns <= nrelax [1] && z < zrelax [0]) || + * (ns <= nrelax [2] && z < zrelax [1]) || (z < zrelax [2]) + * + * Default parameters result in the following rule: + * (ns <= 4) || (no new zero entries added) || + * (ns <= 16 && z < 0.8) || (ns <= 48 && z < 0.1) || (z < 0.05) + */ + + int prefer_zomplex ; /* X = cholmod_solve (sys, L, B, Common) computes + * x=A\b or solves a related system. If L and B are + * both real, then X is real. Otherwise, X is returned as + * CHOLMOD_COMPLEX if Common->prefer_zomplex is FALSE, or + * CHOLMOD_ZOMPLEX if Common->prefer_zomplex is TRUE. This parameter + * is needed because there is no supernodal zomplex L. Suppose the + * caller wants all complex matrices to be stored in zomplex form + * (MATLAB, for example). A supernodal L is returned in complex form + * if A is zomplex. B can be real, and thus X = cholmod_solve (L,B) + * should return X as zomplex. This cannot be inferred from the input + * arguments L and B. Default: FALSE, since all data types are + * supported in CHOLMOD_COMPLEX form and since this is the native type + * of LAPACK and the BLAS. Note that the MATLAB/cholmod.c mexFunction + * sets this parameter to TRUE, since MATLAB matrices are in + * CHOLMOD_ZOMPLEX form. + */ + + int prefer_upper ; /* cholmod_analyze and cholmod_factorize work + * fastest when a symmetric matrix is stored in + * upper triangular form when a fill-reducing ordering is used. In + * MATLAB, this corresponds to how x=A\b works. When the matrix is + * ordered as-is, they work fastest when a symmetric matrix is in lower + * triangular form. In MATLAB, R=chol(A) does the opposite. This + * parameter affects only how cholmod_read returns a symmetric matrix. + * If TRUE (the default case), a symmetric matrix is always returned in + * upper-triangular form (A->stype = 1). */ + + int quick_return_if_not_posdef ; /* if TRUE, the supernodal numeric + * factorization will return quickly if + * the matrix is not positive definite. Default: FALSE. */ + + /* ---------------------------------------------------------------------- */ + /* printing and error handling options */ + /* ---------------------------------------------------------------------- */ + + int print ; /* print level. Default: 3 */ + int precise ; /* if TRUE, print 16 digits. Otherwise print 5 */ + int (*print_function) (const char *, ...) ; /* pointer to printf */ + + int try_catch ; /* if TRUE, then ignore errors; CHOLMOD is in the middle + * of a try/catch block. No error message is printed + * and the Common->error_handler function is not called. */ + + void (*error_handler) (int status, const char *file, + int line, const char *message) ; + + /* Common->error_handler is the user's error handling routine. If not + * NULL, this routine is called if an error occurs in CHOLMOD. status + * can be CHOLMOD_OK (0), negative for a fatal error, and positive for + * a warning. file is a string containing the name of the source code + * file where the error occured, and line is the line number in that + * file. message is a string describing the error in more detail. */ + + /* ---------------------------------------------------------------------- */ + /* ordering options */ + /* ---------------------------------------------------------------------- */ + + /* The cholmod_analyze routine can try many different orderings and select + * the best one. It can also try one ordering method multiple times, with + * different parameter settings. The default is to use three orderings, + * the user's permutation (if provided), AMD which is the fastest ordering + * and generally gives good fill-in, and METIS. CHOLMOD's nested dissection + * (METIS with a constrained AMD) usually gives a better ordering than METIS + * alone (by about 5% to 10%) but it takes more time. + * + * If you know the method that is best for your matrix, set Common->nmethods + * to 1 and set Common->method [0] to the set of parameters for that method. + * If you set it to 1 and do not provide a permutation, then only AMD will + * be called. + * + * If METIS is not available, the default # of methods tried is 2 (the user + * permutation, if any, and AMD). + * + * To try other methods, set Common->nmethods to the number of methods you + * want to try. The suite of default methods and their parameters is + * described in the cholmod_defaults routine, and summarized here: + * + * Common->method [i]: + * i = 0: user-provided ordering (cholmod_analyze_p only) + * i = 1: AMD (for both A and A*A') + * i = 2: METIS + * i = 3: CHOLMOD's nested dissection (NESDIS), default parameters + * i = 4: natural + * i = 5: NESDIS with nd_small = 20000 + * i = 6: NESDIS with nd_small = 4, no constrained minimum degree + * i = 7: NESDIS with no dense node removal + * i = 8: AMD for A, COLAMD for A*A' + * + * You can modify the suite of methods you wish to try by modifying + * Common.method [...] after calling cholmod_start or cholmod_defaults. + * + * For example, to use AMD, followed by a weighted postordering: + * + * Common->nmethods = 1 ; + * Common->method [0].ordering = CHOLMOD_AMD ; + * Common->postorder = TRUE ; + * + * To use the natural ordering (with no postordering): + * + * Common->nmethods = 1 ; + * Common->method [0].ordering = CHOLMOD_NATURAL ; + * Common->postorder = FALSE ; + * + * If you are going to factorize hundreds or more matrices with the same + * nonzero pattern, you may wish to spend a great deal of time finding a + * good permutation. In this case, try setting Common->nmethods to 9. + * The time spent in cholmod_analysis will be very high, but you need to + * call it only once. + * + * cholmod_analyze sets Common->current to a value between 0 and nmethods-1. + * Each ordering method uses the set of options defined by this parameter. + */ + + int nmethods ; /* The number of ordering methods to try. Default: 0. + * nmethods = 0 is a special case. cholmod_analyze + * will try the user-provided ordering (if given) and AMD. Let fl and + * lnz be the flop count and nonzeros in L from AMD's ordering. Let + * anz be the number of nonzeros in the upper or lower triangular part + * of the symmetric matrix A. If fl/lnz < 500 or lnz/anz < 5, then this + * is a good ordering, and METIS is not attempted. Otherwise, METIS is + * tried. The best ordering found is used. If nmethods > 0, the + * methods used are given in the method[ ] array, below. The first + * three methods in the default suite of orderings is (1) use the given + * permutation (if provided), (2) use AMD, and (3) use METIS. Maximum + * allowed value is CHOLMOD_MAXMETHODS. */ + + int current ; /* The current method being tried. Default: 0. Valid + * range is 0 to nmethods-1. */ + + int selected ; /* The best method found. */ + + /* The suite of ordering methods and parameters: */ + + struct cholmod_method_struct + { + /* statistics for this method */ + double lnz ; /* nnz(L) excl. zeros from supernodal amalgamation, + * for a "pure" L */ + + double fl ; /* flop count for a "pure", real simplicial LL' + * factorization, with no extra work due to + * amalgamation. Subtract n to get the LDL' flop count. Multiply + * by about 4 if the matrix is complex or zomplex. */ + + /* ordering method parameters */ + double prune_dense ;/* dense row/col control for AMD, SYMAMD, CSYMAMD, + * and NESDIS (cholmod_nested_dissection). For a + * symmetric n-by-n matrix, rows/columns with more than + * MAX (16, prune_dense * sqrt (n)) entries are removed prior to + * ordering. They appear at the end of the re-ordered matrix. + * + * If prune_dense < 0, only completely dense rows/cols are removed. + * + * This paramater is also the dense column control for COLAMD and + * CCOLAMD. For an m-by-n matrix, columns with more than + * MAX (16, prune_dense * sqrt (MIN (m,n))) entries are removed prior + * to ordering. They appear at the end of the re-ordered matrix. + * CHOLMOD factorizes A*A', so it calls COLAMD and CCOLAMD with A', + * not A. Thus, this parameter affects the dense *row* control for + * CHOLMOD's matrix, and the dense *column* control for COLAMD and + * CCOLAMD. + * + * Removing dense rows and columns improves the run-time of the + * ordering methods. It has some impact on ordering quality + * (usually minimal, sometimes good, sometimes bad). + * + * Default: 10. */ + + double prune_dense2 ;/* dense row control for COLAMD and CCOLAMD. + * Rows with more than MAX (16, dense2 * sqrt (n)) + * for an m-by-n matrix are removed prior to ordering. CHOLMOD's + * matrix is transposed before ordering it with COLAMD or CCOLAMD, + * so this controls the dense *columns* of CHOLMOD's matrix, and + * the dense *rows* of COLAMD's or CCOLAMD's matrix. + * + * If prune_dense2 < 0, only completely dense rows/cols are removed. + * + * Default: -1. Note that this is not the default for COLAMD and + * CCOLAMD. -1 is best for Cholesky. 10 is best for LU. */ + + double nd_oksep ; /* in NESDIS, when a node separator is computed, it + * discarded if nsep >= nd_oksep*n, where nsep is + * the number of nodes in the separator, and n is the size of the + * graph being cut. Valid range is 0 to 1. If 1 or greater, the + * separator is discarded if it consists of the entire graph. + * Default: 1 */ + + double other1 [4] ; /* future expansion */ + + size_t nd_small ; /* do not partition graphs with fewer nodes than + * nd_small, in NESDIS. Default: 200 (same as + * METIS) */ + + size_t other2 [4] ; /* future expansion */ + + int aggressive ; /* Aggresive absorption in AMD, COLAMD, SYMAMD, + * CCOLAMD, and CSYMAMD. Default: TRUE */ + + int order_for_lu ; /* CCOLAMD can be optimized to produce an ordering + * for LU or Cholesky factorization. CHOLMOD only + * performs a Cholesky factorization. However, you may wish to use + * CHOLMOD as an interface for CCOLAMD but use it for your own LU + * factorization. In this case, order_for_lu should be set to FALSE. + * When factorizing in CHOLMOD itself, you should *** NEVER *** set + * this parameter FALSE. Default: TRUE. */ + + int nd_compress ; /* If TRUE, compress the graph and subgraphs before + * partitioning them in NESDIS. Default: TRUE */ + + int nd_camd ; /* If 1, follow the nested dissection ordering + * with a constrained minimum degree ordering that + * respects the partitioning just found (using CAMD). If 2, use + * CSYMAMD instead. If you set nd_small very small, you may not need + * this ordering, and can save time by setting it to zero (no + * constrained minimum degree ordering). Default: 1. */ + + int nd_components ; /* The nested dissection ordering finds a node + * separator that splits the graph into two parts, + * which may be unconnected. If nd_components is TRUE, each of + * these connected components is split independently. If FALSE, + * each part is split as a whole, even if it consists of more than + * one connected component. Default: FALSE */ + + /* fill-reducing ordering to use */ + int ordering ; + + size_t other3 [4] ; /* future expansion */ + + } method [CHOLMOD_MAXMETHODS + 1] ; + + int postorder ; /* If TRUE, cholmod_analyze follows the ordering with a + * weighted postorder of the elimination tree. Improves + * supernode amalgamation. Does not affect fundamental nnz(L) and + * flop count. Default: TRUE. */ + + /* ---------------------------------------------------------------------- */ + /* memory management routines */ + /* ---------------------------------------------------------------------- */ + + void *(*malloc_memory) (size_t) ; /* pointer to malloc */ + void *(*realloc_memory) (void *, size_t) ; /* pointer to realloc */ + void (*free_memory) (void *) ; /* pointer to free */ + void *(*calloc_memory) (size_t, size_t) ; /* pointer to calloc */ + + /* ---------------------------------------------------------------------- */ + /* routines for complex arithmetic */ + /* ---------------------------------------------------------------------- */ + + int (*complex_divide) (double ax, double az, double bx, double bz, + double *cx, double *cz) ; + + /* flag = complex_divide (ax, az, bx, bz, &cx, &cz) computes the complex + * division c = a/b, where ax and az hold the real and imaginary part + * of a, and b and c are stored similarly. flag is returned as 1 if + * a divide-by-zero occurs, or 0 otherwise. By default, the function + * pointer Common->complex_divide is set equal to cholmod_divcomplex. + */ + + double (*hypotenuse) (double x, double y) ; + + /* s = hypotenuse (x,y) computes s = sqrt (x*x + y*y), but does so more + * accurately. By default, the function pointer Common->hypotenuse is + * set equal to cholmod_hypot. See also the hypot function in the C99 + * standard, which has an identical syntax and function. If you have + * a C99-compliant compiler, you can set Common->hypotenuse = hypot. */ + + /* ---------------------------------------------------------------------- */ + /* METIS workarounds */ + /* ---------------------------------------------------------------------- */ + + double metis_memory ; /* This is a parameter for CHOLMOD's interface to + * METIS, not a parameter to METIS itself. METIS + * uses an amount of memory that is difficult to estimate precisely + * beforehand. If it runs out of memory, it terminates your program. + * All routines in CHOLMOD except for CHOLMOD's interface to METIS + * return an error status and safely return to your program if they run + * out of memory. To mitigate this problem, the CHOLMOD interface + * can allocate a single block of memory equal in size to an empirical + * upper bound of METIS's memory usage times the Common->metis_memory + * parameter, and then immediately free it. It then calls METIS. If + * this pre-allocation fails, it is possible that METIS will fail as + * well, and so CHOLMOD returns with an out-of-memory condition without + * calling METIS. + * + * METIS_NodeND (used in the CHOLMOD_METIS ordering option) with its + * default parameter settings typically uses about (4*nz+40n+4096) + * times sizeof(int) memory, where nz is equal to the number of entries + * in A for the symmetric case or AA' if an unsymmetric matrix is + * being ordered (where nz includes both the upper and lower parts + * of A or AA'). The observed "upper bound" (with 2 exceptions), + * measured in an instrumented copy of METIS 4.0.1 on thousands of + * matrices, is (10*nz+50*n+4096) * sizeof(int). Two large matrices + * exceeded this bound, one by almost a factor of 2 (Gupta/gupta2). + * + * If your program is terminated by METIS, try setting metis_memory to + * 2.0, or even higher if needed. By default, CHOLMOD assumes that METIS + * does not have this problem (so that CHOLMOD will work correctly when + * this issue is fixed in METIS). Thus, the default value is zero. + * This work-around is not guaranteed anyway. + * + * If a matrix exceeds this predicted memory usage, AMD is attempted + * instead. It, too, may run out of memory, but if it does so it will + * not terminate your program. + */ + + double metis_dswitch ; /* METIS_NodeND in METIS 4.0.1 gives a seg */ + size_t metis_nswitch ; /* fault with one matrix of order n = 3005 and + * nz = 6,036,025. This is a very dense graph. + * The workaround is to use AMD instead of METIS for matrices of dimension + * greater than Common->metis_nswitch (default 3000) or more and with + * density of Common->metis_dswitch (default 0.66) or more. + * cholmod_nested_dissection has no problems with the same matrix, even + * though it uses METIS_NodeComputeSeparator on this matrix. If this + * seg fault does not affect you, set metis_nswitch to zero or less, + * and CHOLMOD will not switch to AMD based just on the density of the + * matrix (it will still switch to AMD if the metis_memory parameter + * causes the switch). + */ + + /* ---------------------------------------------------------------------- */ + /* workspace */ + /* ---------------------------------------------------------------------- */ + + /* CHOLMOD has several routines that take less time than the size of + * workspace they require. Allocating and initializing the workspace would + * dominate the run time, unless workspace is allocated and initialized + * just once. CHOLMOD allocates this space when needed, and holds it here + * between calls to CHOLMOD. cholmod_start sets these pointers to NULL + * (which is why it must be the first routine called in CHOLMOD). + * cholmod_finish frees the workspace (which is why it must be the last + * call to CHOLMOD). + */ + + size_t nrow ; /* size of Flag and Head */ + UF_long mark ; /* mark value for Flag array */ + size_t iworksize ; /* size of Iwork. Upper bound: 6*nrow+ncol */ + size_t xworksize ; /* size of Xwork, in bytes. + * maxrank*nrow*sizeof(double) for update/downdate. + * 2*nrow*sizeof(double) otherwise */ + + /* initialized workspace: contents needed between calls to CHOLMOD */ + void *Flag ; /* size nrow, an integer array. Kept cleared between + * calls to cholmod rouines (Flag [i] < mark) */ + + void *Head ; /* size nrow+1, an integer array. Kept cleared between + * calls to cholmod routines (Head [i] = EMPTY) */ + + void *Xwork ; /* a double array. Its size varies. It is nrow for + * most routines (cholmod_rowfac, cholmod_add, + * cholmod_aat, cholmod_norm, cholmod_ssmult) for the real case, twice + * that when the input matrices are complex or zomplex. It is of size + * 2*nrow for cholmod_rowadd and cholmod_rowdel. For cholmod_updown, + * its size is maxrank*nrow where maxrank is 2, 4, or 8. Kept cleared + * between calls to cholmod (set to zero). */ + + /* uninitialized workspace, contents not needed between calls to CHOLMOD */ + void *Iwork ; /* size iworksize, 2*nrow+ncol for most routines, + * up to 6*nrow+ncol for cholmod_analyze. */ + + int itype ; /* If CHOLMOD_LONG, Flag, Head, and Iwork are UF_long. + * Otherwise all three arrays are int. */ + + int dtype ; /* double or float */ + + /* Common->itype and Common->dtype are used to define the types of all + * sparse matrices, triplet matrices, dense matrices, and factors + * created using this Common struct. The itypes and dtypes of all + * parameters to all CHOLMOD routines must match. */ + + int no_workspace_reallocate ; /* this is an internal flag, used as a + * precaution by cholmod_analyze. It is normally false. If true, + * cholmod_allocate_work is not allowed to reallocate any workspace; + * they must use the existing workspace in Common (Iwork, Flag, Head, + * and Xwork). Added for CHOLMOD v1.1 */ + + /* ---------------------------------------------------------------------- */ + /* statistics */ + /* ---------------------------------------------------------------------- */ + + /* fl and lnz are set only in cholmod_analyze and cholmod_rowcolcounts, + * in the Cholesky modudle. modfl is set only in the Modify module. */ + + int status ; /* error code */ + double fl ; /* LL' flop count from most recent analysis */ + double lnz ; /* fundamental nz in L */ + double anz ; /* nonzeros in tril(A) if A is symmetric/lower, + * triu(A) if symmetric/upper, or tril(A*A') if + * unsymmetric, in last call to cholmod_analyze. */ + double modfl ; /* flop count from most recent update/downdate/ + * rowadd/rowdel (excluding flops to modify the + * solution to Lx=b, if computed) */ + size_t malloc_count ; /* # of objects malloc'ed minus the # free'd*/ + size_t memory_usage ; /* peak memory usage in bytes */ + size_t memory_inuse ; /* current memory usage in bytes */ + + double nrealloc_col ; /* # of column reallocations */ + double nrealloc_factor ;/* # of factor reallocations due to col. reallocs */ + double ndbounds_hit ; /* # of times diagonal modified by dbound */ + + double rowfacfl ; /* # of flops in last call to cholmod_rowfac */ + double aatfl ; /* # of flops to compute A(:,f)*A(:,f)' */ + + /* ---------------------------------------------------------------------- */ + /* future expansion */ + /* ---------------------------------------------------------------------- */ + + /* To allow CHOLMOD to be updated without recompiling the user application, + * additional space is set aside here for future statistics, parameters, + * and workspace. Note: additional entries were added in v1.1 to the + * method array, above, and thus v1.0 and v1.1 are not binary compatible. + * + * v1.1 to the current version are binary compatible. + */ + + /* ---------------------------------------------------------------------- */ + double other1 [10] ; + + double SPQR_xstat [4] ; /* for SuiteSparseQR statistics */ + + /* SuiteSparseQR control parameters: */ + double SPQR_grain ; /* task size is >= max (total flops / grain) */ + double SPQR_small ; /* task size is >= small */ + + /* ---------------------------------------------------------------------- */ + UF_long SPQR_istat [10] ; /* for SuiteSparseQR statistics */ + UF_long other2 [6] ; /* reduced from size 16 in v1.6 */ + + /* ---------------------------------------------------------------------- */ + int other3 [10] ; /* reduced from size 16 in v1.1. */ + + int prefer_binary ; /* cholmod_read_triplet converts a symmetric + * pattern-only matrix into a real matrix. If + * prefer_binary is FALSE, the diagonal entries are set to 1 + the degree + * of the row/column, and off-diagonal entries are set to -1 (resulting + * in a positive definite matrix if the diagonal is zero-free). Most + * symmetric patterns are the pattern a positive definite matrix. If + * this parameter is TRUE, then the matrix is returned with a 1 in each + * entry, instead. Default: FALSE. Added in v1.3. */ + + /* control parameter (added for v1.2): */ + int default_nesdis ; /* Default: FALSE. If FALSE, then the default + * ordering strategy (when Common->nmethods == 0) + * is to try the given ordering (if present), AMD, and then METIS if AMD + * reports high fill-in. If Common->default_nesdis is TRUE then NESDIS + * is used instead in the default strategy. */ + + /* statistic (added for v1.2): */ + int called_nd ; /* TRUE if the last call to + * cholmod_analyze called NESDIS or METIS. */ + + int blas_ok ; /* FALSE if BLAS int overflow; TRUE otherwise */ + + /* SuiteSparseQR control parameters: */ + int SPQR_shrink ; /* controls stack realloc method */ + int SPQR_nthreads ; /* number of TBB threads, 0 = auto */ + + /* ---------------------------------------------------------------------- */ + size_t other4 [16] ; + + /* ---------------------------------------------------------------------- */ + void *other5 [16] ; + +} cholmod_common ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_start: first call to CHOLMOD */ +/* -------------------------------------------------------------------------- */ + +int cholmod_start +( + cholmod_common *Common +) ; + +int cholmod_l_start (cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_finish: last call to CHOLMOD */ +/* -------------------------------------------------------------------------- */ + +int cholmod_finish +( + cholmod_common *Common +) ; + +int cholmod_l_finish (cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_defaults: restore default parameters */ +/* -------------------------------------------------------------------------- */ + +int cholmod_defaults +( + cholmod_common *Common +) ; + +int cholmod_l_defaults (cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_maxrank: return valid maximum rank for update/downdate */ +/* -------------------------------------------------------------------------- */ + +size_t cholmod_maxrank /* returns validated value of Common->maxrank */ +( + /* ---- input ---- */ + size_t n, /* A and L will have n rows */ + /* --------------- */ + cholmod_common *Common +) ; + +size_t cholmod_l_maxrank (size_t, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_allocate_work: allocate workspace in Common */ +/* -------------------------------------------------------------------------- */ + +int cholmod_allocate_work +( + /* ---- input ---- */ + size_t nrow, /* size: Common->Flag (nrow), Common->Head (nrow+1) */ + size_t iworksize, /* size of Common->Iwork */ + size_t xworksize, /* size of Common->Xwork */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_allocate_work (size_t, size_t, size_t, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_free_work: free workspace in Common */ +/* -------------------------------------------------------------------------- */ + +int cholmod_free_work +( + cholmod_common *Common +) ; + +int cholmod_l_free_work (cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_clear_flag: clear Flag workspace in Common */ +/* -------------------------------------------------------------------------- */ + +/* use a macro for speed */ +#define CHOLMOD_CLEAR_FLAG(Common) \ +{ \ + Common->mark++ ; \ + if (Common->mark <= 0) \ + { \ + Common->mark = EMPTY ; \ + CHOLMOD (clear_flag) (Common) ; \ + } \ +} + +UF_long cholmod_clear_flag +( + cholmod_common *Common +) ; + +UF_long cholmod_l_clear_flag (cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_error: called when CHOLMOD encounters an error */ +/* -------------------------------------------------------------------------- */ + +int cholmod_error +( + /* ---- input ---- */ + int status, /* error status */ + const char *file, /* name of source code file where error occured */ + int line, /* line number in source code file where error occured*/ + const char *message,/* error message */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_error (int, const char *, int, const char *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_dbound: for internal use in CHOLMOD only */ +/* -------------------------------------------------------------------------- */ + +double cholmod_dbound /* returns modified diagonal entry of D or L */ +( + /* ---- input ---- */ + double dj, /* diagonal entry of D for LDL' or L for LL' */ + /* --------------- */ + cholmod_common *Common +) ; + +double cholmod_l_dbound (double, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_hypot: compute sqrt (x*x + y*y) accurately */ +/* -------------------------------------------------------------------------- */ + +double cholmod_hypot +( + /* ---- input ---- */ + double x, double y +) ; + +double cholmod_l_hypot (double, double) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_divcomplex: complex division, c = a/b */ +/* -------------------------------------------------------------------------- */ + +int cholmod_divcomplex /* return 1 if divide-by-zero, 0 otherise */ +( + /* ---- input ---- */ + double ar, double ai, /* real and imaginary parts of a */ + double br, double bi, /* real and imaginary parts of b */ + /* ---- output --- */ + double *cr, double *ci /* real and imaginary parts of c */ +) ; + +int cholmod_l_divcomplex (double, double, double, double, double *, double *) ; + + +/* ========================================================================== */ +/* === Core/cholmod_sparse ================================================== */ +/* ========================================================================== */ + +/* A sparse matrix stored in compressed-column form. */ + +typedef struct cholmod_sparse_struct +{ + size_t nrow ; /* the matrix is nrow-by-ncol */ + size_t ncol ; + size_t nzmax ; /* maximum number of entries in the matrix */ + + /* pointers to int or UF_long: */ + void *p ; /* p [0..ncol], the column pointers */ + void *i ; /* i [0..nzmax-1], the row indices */ + + /* for unpacked matrices only: */ + void *nz ; /* nz [0..ncol-1], the # of nonzeros in each col. In + * packed form, the nonzero pattern of column j is in + * A->i [A->p [j] ... A->p [j+1]-1]. In unpacked form, column j is in + * A->i [A->p [j] ... A->p [j]+A->nz[j]-1] instead. In both cases, the + * numerical values (if present) are in the corresponding locations in + * the array x (or z if A->xtype is CHOLMOD_ZOMPLEX). */ + + /* pointers to double or float: */ + void *x ; /* size nzmax or 2*nzmax, if present */ + void *z ; /* size nzmax, if present */ + + int stype ; /* Describes what parts of the matrix are considered: + * + * 0: matrix is "unsymmetric": use both upper and lower triangular parts + * (the matrix may actually be symmetric in pattern and value, but + * both parts are explicitly stored and used). May be square or + * rectangular. + * >0: matrix is square and symmetric, use upper triangular part. + * Entries in the lower triangular part are ignored. + * <0: matrix is square and symmetric, use lower triangular part. + * Entries in the upper triangular part are ignored. + * + * Note that stype>0 and stype<0 are different for cholmod_sparse and + * cholmod_triplet. See the cholmod_triplet data structure for more + * details. + */ + + int itype ; /* CHOLMOD_INT: p, i, and nz are int. + * CHOLMOD_INTLONG: p is UF_long, i and nz are int. + * CHOLMOD_LONG: p, i, and nz are UF_long. */ + + int xtype ; /* pattern, real, complex, or zomplex */ + int dtype ; /* x and z are double or float */ + int sorted ; /* TRUE if columns are sorted, FALSE otherwise */ + int packed ; /* TRUE if packed (nz ignored), FALSE if unpacked + * (nz is required) */ + +} cholmod_sparse ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_allocate_sparse: allocate a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_allocate_sparse +( + /* ---- input ---- */ + size_t nrow, /* # of rows of A */ + size_t ncol, /* # of columns of A */ + size_t nzmax, /* max # of nonzeros of A */ + int sorted, /* TRUE if columns of A sorted, FALSE otherwise */ + int packed, /* TRUE if A will be packed, FALSE otherwise */ + int stype, /* stype of A */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_allocate_sparse (size_t, size_t, size_t, int, int, + int, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_free_sparse: free a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_free_sparse +( + /* ---- in/out --- */ + cholmod_sparse **A, /* matrix to deallocate, NULL on output */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_free_sparse (cholmod_sparse **, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_reallocate_sparse: change the size (# entries) of sparse matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_reallocate_sparse +( + /* ---- input ---- */ + size_t nznew, /* new # of entries in A */ + /* ---- in/out --- */ + cholmod_sparse *A, /* matrix to reallocate */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_reallocate_sparse ( size_t, cholmod_sparse *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_nnz: return number of nonzeros in a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +UF_long cholmod_nnz +( + /* ---- input ---- */ + cholmod_sparse *A, + /* --------------- */ + cholmod_common *Common +) ; + +UF_long cholmod_l_nnz (cholmod_sparse *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_speye: sparse identity matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_speye +( + /* ---- input ---- */ + size_t nrow, /* # of rows of A */ + size_t ncol, /* # of columns of A */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_speye (size_t, size_t, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_spzeros: sparse zero matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_spzeros +( + /* ---- input ---- */ + size_t nrow, /* # of rows of A */ + size_t ncol, /* # of columns of A */ + size_t nzmax, /* max # of nonzeros of A */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_spzeros (size_t, size_t, size_t, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_transpose: transpose a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +/* Return A' or A.' The "values" parameter is 0, 1, or 2 to denote the pattern + * transpose, the array transpose (A.'), and the complex conjugate transpose + * (A'). + */ + +cholmod_sparse *cholmod_transpose +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to transpose */ + int values, /* 0: pattern, 1: array transpose, 2: conj. transpose */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_transpose (cholmod_sparse *, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_transpose_unsym: transpose an unsymmetric sparse matrix */ +/* -------------------------------------------------------------------------- */ + +/* Compute F = A', A (:,f)', or A (p,f)', where A is unsymmetric and F is + * already allocated. See cholmod_transpose for a simpler routine. */ + +int cholmod_transpose_unsym +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to transpose */ + int values, /* 0: pattern, 1: array transpose, 2: conj. transpose */ + int *Perm, /* size nrow, if present (can be NULL) */ + int *fset, /* subset of 0:(A->ncol)-1 */ + size_t fsize, /* size of fset */ + /* ---- output --- */ + cholmod_sparse *F, /* F = A', A(:,f)', or A(p,f)' */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_transpose_unsym (cholmod_sparse *, int, UF_long *, UF_long *, + size_t, cholmod_sparse *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_transpose_sym: transpose a symmetric sparse matrix */ +/* -------------------------------------------------------------------------- */ + +/* Compute F = A' or A (p,p)', where A is symmetric and F is already allocated. + * See cholmod_transpose for a simpler routine. */ + +int cholmod_transpose_sym +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to transpose */ + int values, /* 0: pattern, 1: array transpose, 2: conj. transpose */ + int *Perm, /* size nrow, if present (can be NULL) */ + /* ---- output --- */ + cholmod_sparse *F, /* F = A' or A(p,p)' */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_transpose_sym (cholmod_sparse *, int, UF_long *, cholmod_sparse *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_ptranspose: transpose a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +/* Return A' or A(p,p)' if A is symmetric. Return A', A(:,f)', or A(p,f)' if + * A is unsymmetric. */ + +cholmod_sparse *cholmod_ptranspose +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to transpose */ + int values, /* 0: pattern, 1: array transpose, 2: conj. transpose */ + int *Perm, /* if non-NULL, F = A(p,f) or A(p,p) */ + int *fset, /* subset of 0:(A->ncol)-1 */ + size_t fsize, /* size of fset */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_ptranspose (cholmod_sparse *, int, UF_long *, + UF_long *, size_t, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_sort: sort row indices in each column of sparse matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_sort +( + /* ---- in/out --- */ + cholmod_sparse *A, /* matrix to sort */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_sort (cholmod_sparse *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_band: C = tril (triu (A,k1), k2) */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_band +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to extract band matrix from */ + UF_long k1, /* ignore entries below the k1-st diagonal */ + UF_long k2, /* ignore entries above the k2-nd diagonal */ + int mode, /* >0: numerical, 0: pattern, <0: pattern (no diag) */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_band (cholmod_sparse *, UF_long, UF_long, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_band_inplace: A = tril (triu (A,k1), k2) */ +/* -------------------------------------------------------------------------- */ + +int cholmod_band_inplace +( + /* ---- input ---- */ + UF_long k1, /* ignore entries below the k1-st diagonal */ + UF_long k2, /* ignore entries above the k2-nd diagonal */ + int mode, /* >0: numerical, 0: pattern, <0: pattern (no diag) */ + /* ---- in/out --- */ + cholmod_sparse *A, /* matrix from which entries not in band are removed */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_band_inplace (UF_long, UF_long, int, cholmod_sparse *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_aat: C = A*A' or A(:,f)*A(:,f)' */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_aat +( + /* ---- input ---- */ + cholmod_sparse *A, /* input matrix; C=A*A' is constructed */ + int *fset, /* subset of 0:(A->ncol)-1 */ + size_t fsize, /* size of fset */ + int mode, /* >0: numerical, 0: pattern, <0: pattern (no diag), + * -2: pattern only, no diagonal, add 50%+n extra + * space to C */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_aat (cholmod_sparse *, UF_long *, size_t, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy_sparse: C = A, create an exact copy of a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_copy_sparse +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_copy_sparse (cholmod_sparse *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy: C = A, with possible change of stype */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_copy +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to copy */ + int stype, /* requested stype of C */ + int mode, /* >0: numerical, 0: pattern, <0: pattern (no diag) */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_copy (cholmod_sparse *, int, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_add: C = alpha*A + beta*B */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_add +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to add */ + cholmod_sparse *B, /* matrix to add */ + double alpha [2], /* scale factor for A */ + double beta [2], /* scale factor for B */ + int values, /* if TRUE compute the numerical values of C */ + int sorted, /* if TRUE, sort columns of C */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_add (cholmod_sparse *, cholmod_sparse *, double *, + double *, int, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_sparse_xtype: change the xtype of a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_sparse_xtype +( + /* ---- input ---- */ + int to_xtype, /* requested xtype (pattern, real, complex, zomplex) */ + /* ---- in/out --- */ + cholmod_sparse *A, /* sparse matrix to change */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_sparse_xtype (int, cholmod_sparse *, cholmod_common *) ; + + +/* ========================================================================== */ +/* === Core/cholmod_factor ================================================== */ +/* ========================================================================== */ + +/* A symbolic and numeric factorization, either simplicial or supernodal. + * In all cases, the row indices in the columns of L are kept sorted. */ + +typedef struct cholmod_factor_struct +{ + /* ---------------------------------------------------------------------- */ + /* for both simplicial and supernodal factorizations */ + /* ---------------------------------------------------------------------- */ + + size_t n ; /* L is n-by-n */ + + size_t minor ; /* If the factorization failed, L->minor is the column + * at which it failed (in the range 0 to n-1). A value + * of n means the factorization was successful or + * the matrix has not yet been factorized. */ + + /* ---------------------------------------------------------------------- */ + /* symbolic ordering and analysis */ + /* ---------------------------------------------------------------------- */ + + void *Perm ; /* size n, permutation used */ + void *ColCount ; /* size n, column counts for simplicial L */ + + /* ---------------------------------------------------------------------- */ + /* simplicial factorization */ + /* ---------------------------------------------------------------------- */ + + size_t nzmax ; /* size of i and x */ + + void *p ; /* p [0..ncol], the column pointers */ + void *i ; /* i [0..nzmax-1], the row indices */ + void *x ; /* x [0..nzmax-1], the numerical values */ + void *z ; + void *nz ; /* nz [0..ncol-1], the # of nonzeros in each column. + * i [p [j] ... p [j]+nz[j]-1] contains the row indices, + * and the numerical values are in the same locatins + * in x. The value of i [p [k]] is always k. */ + + void *next ; /* size ncol+2. next [j] is the next column in i/x */ + void *prev ; /* size ncol+2. prev [j] is the prior column in i/x. + * head of the list is ncol+1, and the tail is ncol. */ + + /* ---------------------------------------------------------------------- */ + /* supernodal factorization */ + /* ---------------------------------------------------------------------- */ + + /* Note that L->x is shared with the simplicial data structure. L->x has + * size L->nzmax for a simplicial factor, and size L->xsize for a supernodal + * factor. */ + + size_t nsuper ; /* number of supernodes */ + size_t ssize ; /* size of s, integer part of supernodes */ + size_t xsize ; /* size of x, real part of supernodes */ + size_t maxcsize ; /* size of largest update matrix */ + size_t maxesize ; /* max # of rows in supernodes, excl. triangular part */ + + void *super ; /* size nsuper+1, first col in each supernode */ + void *pi ; /* size nsuper+1, pointers to integer patterns */ + void *px ; /* size nsuper+1, pointers to real parts */ + void *s ; /* size ssize, integer part of supernodes */ + + /* ---------------------------------------------------------------------- */ + /* factorization type */ + /* ---------------------------------------------------------------------- */ + + int ordering ; /* ordering method used */ + + int is_ll ; /* TRUE if LL', FALSE if LDL' */ + int is_super ; /* TRUE if supernodal, FALSE if simplicial */ + int is_monotonic ; /* TRUE if columns of L appear in order 0..n-1. + * Only applicable to simplicial numeric types. */ + + /* There are 8 types of factor objects that cholmod_factor can represent + * (only 6 are used): + * + * Numeric types (xtype is not CHOLMOD_PATTERN) + * -------------------------------------------- + * + * simplicial LDL': (is_ll FALSE, is_super FALSE). Stored in compressed + * column form, using the simplicial components above (nzmax, p, i, + * x, z, nz, next, and prev). The unit diagonal of L is not stored, + * and D is stored in its place. There are no supernodes. + * + * simplicial LL': (is_ll TRUE, is_super FALSE). Uses the same storage + * scheme as the simplicial LDL', except that D does not appear. + * The first entry of each column of L is the diagonal entry of + * that column of L. + * + * supernodal LDL': (is_ll FALSE, is_super TRUE). Not used. + * FUTURE WORK: add support for supernodal LDL' + * + * supernodal LL': (is_ll TRUE, is_super TRUE). A supernodal factor, + * using the supernodal components described above (nsuper, ssize, + * xsize, maxcsize, maxesize, super, pi, px, s, x, and z). + * + * + * Symbolic types (xtype is CHOLMOD_PATTERN) + * ----------------------------------------- + * + * simplicial LDL': (is_ll FALSE, is_super FALSE). Nothing is present + * except Perm and ColCount. + * + * simplicial LL': (is_ll TRUE, is_super FALSE). Identical to the + * simplicial LDL', except for the is_ll flag. + * + * supernodal LDL': (is_ll FALSE, is_super TRUE). Not used. + * FUTURE WORK: add support for supernodal LDL' + * + * supernodal LL': (is_ll TRUE, is_super TRUE). A supernodal symbolic + * factorization. The simplicial symbolic information is present + * (Perm and ColCount), as is all of the supernodal factorization + * except for the numerical values (x and z). + */ + + int itype ; /* The integer arrays are Perm, ColCount, p, i, nz, + * next, prev, super, pi, px, and s. If itype is + * CHOLMOD_INT, all of these are int arrays. + * CHOLMOD_INTLONG: p, pi, px are UF_long, others int. + * CHOLMOD_LONG: all integer arrays are UF_long. */ + int xtype ; /* pattern, real, complex, or zomplex */ + int dtype ; /* x and z double or float */ + +} cholmod_factor ; + + +/* -------------------------------------------------------------------------- */ +/* cholmod_allocate_factor: allocate a factor (symbolic LL' or LDL') */ +/* -------------------------------------------------------------------------- */ + +cholmod_factor *cholmod_allocate_factor +( + /* ---- input ---- */ + size_t n, /* L is n-by-n */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_factor *cholmod_l_allocate_factor (size_t, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_free_factor: free a factor */ +/* -------------------------------------------------------------------------- */ + +int cholmod_free_factor +( + /* ---- in/out --- */ + cholmod_factor **L, /* factor to free, NULL on output */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_free_factor (cholmod_factor **, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_reallocate_factor: change the # entries in a factor */ +/* -------------------------------------------------------------------------- */ + +int cholmod_reallocate_factor +( + /* ---- input ---- */ + size_t nznew, /* new # of entries in L */ + /* ---- in/out --- */ + cholmod_factor *L, /* factor to modify */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_reallocate_factor (size_t, cholmod_factor *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_change_factor: change the type of factor (e.g., LDL' to LL') */ +/* -------------------------------------------------------------------------- */ + +int cholmod_change_factor +( + /* ---- input ---- */ + int to_xtype, /* to CHOLMOD_PATTERN, _REAL, _COMPLEX, _ZOMPLEX */ + int to_ll, /* TRUE: convert to LL', FALSE: LDL' */ + int to_super, /* TRUE: convert to supernodal, FALSE: simplicial */ + int to_packed, /* TRUE: pack simplicial columns, FALSE: do not pack */ + int to_monotonic, /* TRUE: put simplicial columns in order, FALSE: not */ + /* ---- in/out --- */ + cholmod_factor *L, /* factor to modify */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_change_factor ( int, int, int, int, int, cholmod_factor *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_pack_factor: pack the columns of a factor */ +/* -------------------------------------------------------------------------- */ + +/* Pack the columns of a simplicial factor. Unlike cholmod_change_factor, + * it can pack the columns of a factor even if they are not stored in their + * natural order (non-monotonic). */ + +int cholmod_pack_factor +( + /* ---- in/out --- */ + cholmod_factor *L, /* factor to modify */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_pack_factor (cholmod_factor *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_reallocate_column: resize a single column of a factor */ +/* -------------------------------------------------------------------------- */ + +int cholmod_reallocate_column +( + /* ---- input ---- */ + size_t j, /* the column to reallocate */ + size_t need, /* required size of column j */ + /* ---- in/out --- */ + cholmod_factor *L, /* factor to modify */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_reallocate_column (size_t, size_t, cholmod_factor *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_factor_to_sparse: create a sparse matrix copy of a factor */ +/* -------------------------------------------------------------------------- */ + +/* Only operates on numeric factors, not symbolic ones */ + +cholmod_sparse *cholmod_factor_to_sparse +( + /* ---- in/out --- */ + cholmod_factor *L, /* factor to copy, converted to symbolic on output */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_factor_to_sparse (cholmod_factor *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy_factor: create a copy of a factor */ +/* -------------------------------------------------------------------------- */ + +cholmod_factor *cholmod_copy_factor +( + /* ---- input ---- */ + cholmod_factor *L, /* factor to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_factor *cholmod_l_copy_factor (cholmod_factor *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_factor_xtype: change the xtype of a factor */ +/* -------------------------------------------------------------------------- */ + +int cholmod_factor_xtype +( + /* ---- input ---- */ + int to_xtype, /* requested xtype (real, complex, or zomplex) */ + /* ---- in/out --- */ + cholmod_factor *L, /* factor to change */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_factor_xtype (int, cholmod_factor *, cholmod_common *) ; + + +/* ========================================================================== */ +/* === Core/cholmod_dense =================================================== */ +/* ========================================================================== */ + +/* A dense matrix in column-oriented form. It has no itype since it contains + * no integers. Entry in row i and column j is located in x [i+j*d]. + */ + +typedef struct cholmod_dense_struct +{ + size_t nrow ; /* the matrix is nrow-by-ncol */ + size_t ncol ; + size_t nzmax ; /* maximum number of entries in the matrix */ + size_t d ; /* leading dimension (d >= nrow must hold) */ + void *x ; /* size nzmax or 2*nzmax, if present */ + void *z ; /* size nzmax, if present */ + int xtype ; /* pattern, real, complex, or zomplex */ + int dtype ; /* x and z double or float */ + +} cholmod_dense ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_allocate_dense: allocate a dense matrix (contents uninitialized) */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_allocate_dense +( + /* ---- input ---- */ + size_t nrow, /* # of rows of matrix */ + size_t ncol, /* # of columns of matrix */ + size_t d, /* leading dimension */ + int xtype, /* CHOLMOD_REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_allocate_dense (size_t, size_t, size_t, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_zeros: allocate a dense matrix and set it to zero */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_zeros +( + /* ---- input ---- */ + size_t nrow, /* # of rows of matrix */ + size_t ncol, /* # of columns of matrix */ + int xtype, /* CHOLMOD_REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_zeros (size_t, size_t, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_ones: allocate a dense matrix and set it to all ones */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_ones +( + /* ---- input ---- */ + size_t nrow, /* # of rows of matrix */ + size_t ncol, /* # of columns of matrix */ + int xtype, /* CHOLMOD_REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_ones (size_t, size_t, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_eye: allocate a dense matrix and set it to the identity matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_eye +( + /* ---- input ---- */ + size_t nrow, /* # of rows of matrix */ + size_t ncol, /* # of columns of matrix */ + int xtype, /* CHOLMOD_REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_eye (size_t, size_t, int, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_free_dense: free a dense matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_free_dense +( + /* ---- in/out --- */ + cholmod_dense **X, /* dense matrix to deallocate, NULL on output */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_free_dense (cholmod_dense **, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_sparse_to_dense: create a dense matrix copy of a sparse matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_sparse_to_dense +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_sparse_to_dense (cholmod_sparse *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_dense_to_sparse: create a sparse matrix copy of a dense matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_dense_to_sparse +( + /* ---- input ---- */ + cholmod_dense *X, /* matrix to copy */ + int values, /* TRUE if values to be copied, FALSE otherwise */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_dense_to_sparse (cholmod_dense *, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy_dense: create a copy of a dense matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_dense *cholmod_copy_dense +( + /* ---- input ---- */ + cholmod_dense *X, /* matrix to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_dense *cholmod_l_copy_dense (cholmod_dense *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy_dense2: copy a dense matrix (pre-allocated) */ +/* -------------------------------------------------------------------------- */ + +int cholmod_copy_dense2 +( + /* ---- input ---- */ + cholmod_dense *X, /* matrix to copy */ + /* ---- output --- */ + cholmod_dense *Y, /* copy of matrix X */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_copy_dense2 (cholmod_dense *, cholmod_dense *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_dense_xtype: change the xtype of a dense matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_dense_xtype +( + /* ---- input ---- */ + int to_xtype, /* requested xtype (real, complex,or zomplex) */ + /* ---- in/out --- */ + cholmod_dense *X, /* dense matrix to change */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_dense_xtype (int, cholmod_dense *, cholmod_common *) ; + + +/* ========================================================================== */ +/* === Core/cholmod_triplet ================================================= */ +/* ========================================================================== */ + +/* A sparse matrix stored in triplet form. */ + +typedef struct cholmod_triplet_struct +{ + size_t nrow ; /* the matrix is nrow-by-ncol */ + size_t ncol ; + size_t nzmax ; /* maximum number of entries in the matrix */ + size_t nnz ; /* number of nonzeros in the matrix */ + + void *i ; /* i [0..nzmax-1], the row indices */ + void *j ; /* j [0..nzmax-1], the column indices */ + void *x ; /* size nzmax or 2*nzmax, if present */ + void *z ; /* size nzmax, if present */ + + int stype ; /* Describes what parts of the matrix are considered: + * + * 0: matrix is "unsymmetric": use both upper and lower triangular parts + * (the matrix may actually be symmetric in pattern and value, but + * both parts are explicitly stored and used). May be square or + * rectangular. + * >0: matrix is square and symmetric. Entries in the lower triangular + * part are transposed and added to the upper triangular part when + * the matrix is converted to cholmod_sparse form. + * <0: matrix is square and symmetric. Entries in the upper triangular + * part are transposed and added to the lower triangular part when + * the matrix is converted to cholmod_sparse form. + * + * Note that stype>0 and stype<0 are different for cholmod_sparse and + * cholmod_triplet. The reason is simple. You can permute a symmetric + * triplet matrix by simply replacing a row and column index with their + * new row and column indices, via an inverse permutation. Suppose + * P = L->Perm is your permutation, and Pinv is an array of size n. + * Suppose a symmetric matrix A is represent by a triplet matrix T, with + * entries only in the upper triangular part. Then the following code: + * + * Ti = T->i ; + * Tj = T->j ; + * for (k = 0 ; k < n ; k++) Pinv [P [k]] = k ; + * for (k = 0 ; k < nz ; k++) Ti [k] = Pinv [Ti [k]] ; + * for (k = 0 ; k < nz ; k++) Tj [k] = Pinv [Tj [k]] ; + * + * creates the triplet form of C=P*A*P'. However, if T initially + * contains just the upper triangular entries (T->stype = 1), after + * permutation it has entries in both the upper and lower triangular + * parts. These entries should be transposed when constructing the + * cholmod_sparse form of A, which is what cholmod_triplet_to_sparse + * does. Thus: + * + * C = cholmod_triplet_to_sparse (T, 0, &Common) ; + * + * will return the matrix C = P*A*P'. + * + * Since the triplet matrix T is so simple to generate, it's quite easy + * to remove entries that you do not want, prior to converting T to the + * cholmod_sparse form. So if you include these entries in T, CHOLMOD + * assumes that there must be a reason (such as the one above). Thus, + * no entry in a triplet matrix is ever ignored. + */ + + int itype ; /* CHOLMOD_LONG: i and j are UF_long. Otherwise int. */ + int xtype ; /* pattern, real, complex, or zomplex */ + int dtype ; /* x and z are double or float */ + +} cholmod_triplet ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_allocate_triplet: allocate a triplet matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_triplet *cholmod_allocate_triplet +( + /* ---- input ---- */ + size_t nrow, /* # of rows of T */ + size_t ncol, /* # of columns of T */ + size_t nzmax, /* max # of nonzeros of T */ + int stype, /* stype of T */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_triplet *cholmod_l_allocate_triplet (size_t, size_t, size_t, int, int, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_free_triplet: free a triplet matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_free_triplet +( + /* ---- in/out --- */ + cholmod_triplet **T, /* triplet matrix to deallocate, NULL on output */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_free_triplet (cholmod_triplet **, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_reallocate_triplet: change the # of entries in a triplet matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_reallocate_triplet +( + /* ---- input ---- */ + size_t nznew, /* new # of entries in T */ + /* ---- in/out --- */ + cholmod_triplet *T, /* triplet matrix to modify */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_reallocate_triplet (size_t, cholmod_triplet *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_sparse_to_triplet: create a triplet matrix copy of a sparse matrix*/ +/* -------------------------------------------------------------------------- */ + +cholmod_triplet *cholmod_sparse_to_triplet +( + /* ---- input ---- */ + cholmod_sparse *A, /* matrix to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_triplet *cholmod_l_sparse_to_triplet (cholmod_sparse *, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_triplet_to_sparse: create a sparse matrix copy of a triplet matrix*/ +/* -------------------------------------------------------------------------- */ + +cholmod_sparse *cholmod_triplet_to_sparse +( + /* ---- input ---- */ + cholmod_triplet *T, /* matrix to copy */ + size_t nzmax, /* allocate at least this much space in output matrix */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_sparse *cholmod_l_triplet_to_sparse (cholmod_triplet *, size_t, + cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_copy_triplet: create a copy of a triplet matrix */ +/* -------------------------------------------------------------------------- */ + +cholmod_triplet *cholmod_copy_triplet +( + /* ---- input ---- */ + cholmod_triplet *T, /* matrix to copy */ + /* --------------- */ + cholmod_common *Common +) ; + +cholmod_triplet *cholmod_l_copy_triplet (cholmod_triplet *, cholmod_common *) ; + +/* -------------------------------------------------------------------------- */ +/* cholmod_triplet_xtype: change the xtype of a triplet matrix */ +/* -------------------------------------------------------------------------- */ + +int cholmod_triplet_xtype +( + /* ---- input ---- */ + int to_xtype, /* requested xtype (pattern, real, complex,or zomplex)*/ + /* ---- in/out --- */ + cholmod_triplet *T, /* triplet matrix to change */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_triplet_xtype (int, cholmod_triplet *, cholmod_common *) ; + + +/* ========================================================================== */ +/* === Core/cholmod_memory ================================================== */ +/* ========================================================================== */ + +/* The user may make use of these, just like malloc and free. You can even + * malloc an object and safely free it with cholmod_free, and visa versa + * (except that the memory usage statistics will be corrupted). These routines + * do differ from malloc and free. If cholmod_free is given a NULL pointer, + * for example, it does nothing (unlike the ANSI free). cholmod_realloc does + * not return NULL if given a non-NULL pointer and a nonzero size, even if it + * fails (it returns the original pointer and sets an error code in + * Common->status instead). + * + * CHOLMOD keeps track of the amount of memory it has allocated, and so the + * cholmod_free routine also takes the size of the object being freed. This + * is only used for statistics. If you, the user of CHOLMOD, pass the wrong + * size, the only consequence is that the memory usage statistics will be + * corrupted. + */ + +void *cholmod_malloc /* returns pointer to the newly malloc'd block */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* --------------- */ + cholmod_common *Common +) ; + +void *cholmod_l_malloc (size_t, size_t, cholmod_common *) ; + +void *cholmod_calloc /* returns pointer to the newly calloc'd block */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* --------------- */ + cholmod_common *Common +) ; + +void *cholmod_l_calloc (size_t, size_t, cholmod_common *) ; + +void *cholmod_free /* always returns NULL */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* ---- in/out --- */ + void *p, /* block of memory to free */ + /* --------------- */ + cholmod_common *Common +) ; + +void *cholmod_l_free (size_t, size_t, void *, cholmod_common *) ; + +void *cholmod_realloc /* returns pointer to reallocated block */ +( + /* ---- input ---- */ + size_t nnew, /* requested # of items in reallocated block */ + size_t size, /* size of each item */ + /* ---- in/out --- */ + void *p, /* block of memory to realloc */ + size_t *n, /* current size on input, nnew on output if successful*/ + /* --------------- */ + cholmod_common *Common +) ; + +void *cholmod_l_realloc (size_t, size_t, void *, size_t *, cholmod_common *) ; + +int cholmod_realloc_multiple +( + /* ---- input ---- */ + size_t nnew, /* requested # of items in reallocated blocks */ + int nint, /* number of int/UF_long blocks */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* ---- in/out --- */ + void **I, /* int or UF_long block */ + void **J, /* int or UF_long block */ + void **X, /* complex, double, or float block */ + void **Z, /* zomplex case only: double or float block */ + size_t *n, /* current size of the I,J,X,Z blocks on input, + * nnew on output if successful */ + /* --------------- */ + cholmod_common *Common +) ; + +int cholmod_l_realloc_multiple (size_t, int, int, void **, void **, void **, + void **, size_t *, cholmod_common *) ; + +/* ========================================================================== */ +/* === symmetry types ======================================================= */ +/* ========================================================================== */ + +#define CHOLMOD_MM_RECTANGULAR 1 +#define CHOLMOD_MM_UNSYMMETRIC 2 +#define CHOLMOD_MM_SYMMETRIC 3 +#define CHOLMOD_MM_HERMITIAN 4 +#define CHOLMOD_MM_SKEW_SYMMETRIC 5 +#define CHOLMOD_MM_SYMMETRIC_POSDIAG 6 +#define CHOLMOD_MM_HERMITIAN_POSDIAG 7 + +/* ========================================================================== */ +/* === Numerical relop macros =============================================== */ +/* ========================================================================== */ + +/* These macros correctly handle the NaN case. + * + * CHOLMOD_IS_NAN(x): + * True if x is NaN. False otherwise. The commonly-existing isnan(x) + * function could be used, but it's not in Kernighan & Ritchie 2nd edition + * (ANSI C89). It may appear in , but I'm not certain about + * portability. The expression x != x is true if and only if x is NaN, + * according to the IEEE 754 floating-point standard. + * + * CHOLMOD_IS_ZERO(x): + * True if x is zero. False if x is nonzero, NaN, or +/- Inf. + * This is (x == 0) if the compiler is IEEE 754 compliant. + * + * CHOLMOD_IS_NONZERO(x): + * True if x is nonzero, NaN, or +/- Inf. False if x zero. + * This is (x != 0) if the compiler is IEEE 754 compliant. + * + * CHOLMOD_IS_LT_ZERO(x): + * True if x is < zero or -Inf. False if x is >= 0, NaN, or +Inf. + * This is (x < 0) if the compiler is IEEE 754 compliant. + * + * CHOLMOD_IS_GT_ZERO(x): + * True if x is > zero or +Inf. False if x is <= 0, NaN, or -Inf. + * This is (x > 0) if the compiler is IEEE 754 compliant. + * + * CHOLMOD_IS_LE_ZERO(x): + * True if x is <= zero or -Inf. False if x is > 0, NaN, or +Inf. + * This is (x <= 0) if the compiler is IEEE 754 compliant. + */ + +#ifdef CHOLMOD_WINDOWS + +/* Yes, this is exceedingly ugly. Blame Microsoft, which hopelessly */ +/* violates the IEEE 754 floating-point standard in a bizarre way. */ +/* If you're using an IEEE 754-compliant compiler, then x != x is true */ +/* iff x is NaN. For Microsoft, (x < x) is true iff x is NaN. */ +/* So either way, this macro safely detects a NaN. */ +#define CHOLMOD_IS_NAN(x) (((x) != (x)) || (((x) < (x)))) +#define CHOLMOD_IS_ZERO(x) (((x) == 0.) && !CHOLMOD_IS_NAN(x)) +#define CHOLMOD_IS_NONZERO(x) (((x) != 0.) || CHOLMOD_IS_NAN(x)) +#define CHOLMOD_IS_LT_ZERO(x) (((x) < 0.) && !CHOLMOD_IS_NAN(x)) +#define CHOLMOD_IS_GT_ZERO(x) (((x) > 0.) && !CHOLMOD_IS_NAN(x)) +#define CHOLMOD_IS_LE_ZERO(x) (((x) <= 0.) && !CHOLMOD_IS_NAN(x)) + +#else + +/* These all work properly, according to the IEEE 754 standard ... except on */ +/* a PC with windows. Works fine in Linux on the same PC... */ +#define CHOLMOD_IS_NAN(x) ((x) != (x)) +#define CHOLMOD_IS_ZERO(x) ((x) == 0.) +#define CHOLMOD_IS_NONZERO(x) ((x) != 0.) +#define CHOLMOD_IS_LT_ZERO(x) ((x) < 0.) +#define CHOLMOD_IS_GT_ZERO(x) ((x) > 0.) +#define CHOLMOD_IS_LE_ZERO(x) ((x) <= 0.) + +#endif + +#endif diff --git a/spqr_mini/cholmod_internal.h b/spqr_mini/cholmod_internal.h new file mode 100644 index 000000000..7a89bd5e0 --- /dev/null +++ b/spqr_mini/cholmod_internal.h @@ -0,0 +1,400 @@ +/* ========================================================================== */ +/* === Include/cholmod_internal.h =========================================== */ +/* ========================================================================== */ + +/* ----------------------------------------------------------------------------- + * CHOLMOD/Include/cholmod_internal.h. + * Copyright (C) 2005-2006, Univ. of Florida. Author: Timothy A. Davis + * CHOLMOD/Include/cholmod_internal.h is licensed under Version 2.1 of the GNU + * Lesser General Public License. See lesser.txt for a text of the license. + * CHOLMOD is also available under other licenses; contact authors for details. + * http://www.cise.ufl.edu/research/sparse + * -------------------------------------------------------------------------- */ + +/* CHOLMOD internal include file. + * + * This file contains internal definitions for CHOLMOD, not meant to be included + * in user code. They define macros that are not prefixed with CHOLMOD_. This + * file can safely #include'd in user code if you want to make use of the + * macros defined here, and don't mind the possible name conflicts with your + * code, however. + * + * Required by all CHOLMOD routines. Not required by any user routine that + * uses CHOLMOMD. Unless debugging is enabled, this file does not require any + * CHOLMOD module (not even the Core module). + * + * If debugging is enabled, all CHOLMOD modules require the Check module. + * Enabling debugging requires that this file be editted. Debugging cannot be + * enabled with a compiler flag. This is because CHOLMOD is exceedingly slow + * when debugging is enabled. Debugging is meant for development of CHOLMOD + * itself, not by users of CHOLMOD. + */ + +#ifndef CHOLMOD_INTERNAL_H +#define CHOLMOD_INTERNAL_H + +/* ========================================================================== */ +/* === large file I/O ======================================================= */ +/* ========================================================================== */ + +/* Definitions for large file I/O must come before any other #includes. If + * this causes problems (may not be portable to all platforms), then compile + * CHOLMOD with -DNLARGEFILE. You must do this for MATLAB 6.5 and earlier, + * for example. */ + +//#include "cholmod_io64.h" + +/* ========================================================================== */ +/* === debugging and basic includes ========================================= */ +/* ========================================================================== */ + +/* turn off debugging */ +#ifndef NDEBUG +#define NDEBUG +#endif + +/* Uncomment this line to enable debugging. CHOLMOD will be very slow. +#undef NDEBUG + */ + +#ifdef MATLAB_MEX_FILE +#include "mex.h" +#endif + +#if !defined(NPRINT) || !defined(NDEBUG) +#include +#endif + +#include +#include +#include +#include +#include + +/* ========================================================================== */ +/* === basic definitions ==================================================== */ +/* ========================================================================== */ + +/* Some non-conforming compilers insist on defining TRUE and FALSE. */ +#undef TRUE +#undef FALSE +#define TRUE 1 +#define FALSE 0 +#define BOOLEAN(x) ((x) ? TRUE : FALSE) + +/* NULL should already be defined, but ensure it is here. */ +#ifndef NULL +#define NULL ((void *) 0) +#endif + +/* FLIP is a "negation about -1", and is used to mark an integer i that is + * normally non-negative. FLIP (EMPTY) is EMPTY. FLIP of a number > EMPTY + * is negative, and FLIP of a number < EMTPY is positive. FLIP (FLIP (i)) = i + * for all integers i. UNFLIP (i) is >= EMPTY. */ +#define EMPTY (-1) +#define FLIP(i) (-(i)-2) +#define UNFLIP(i) (((i) < EMPTY) ? FLIP (i) : (i)) + +/* MAX and MIN are not safe to use for NaN's */ +#define MAX(a,b) (((a) > (b)) ? (a) : (b)) +#define MAX3(a,b,c) (((a) > (b)) ? (MAX (a,c)) : (MAX (b,c))) +#define MAX4(a,b,c,d) (((a) > (b)) ? (MAX3 (a,c,d)) : (MAX3 (b,c,d))) +#define MIN(a,b) (((a) < (b)) ? (a) : (b)) +#define IMPLIES(p,q) (!(p) || (q)) + +/* find the sign: -1 if x < 0, 1 if x > 0, zero otherwise. + * Not safe for NaN's */ +#define SIGN(x) (((x) < 0) ? (-1) : (((x) > 0) ? 1 : 0)) + +/* round up an integer x to a multiple of s */ +#define ROUNDUP(x,s) ((s) * (((x) + ((s) - 1)) / (s))) + +#define ERROR(status,msg) \ + CHOLMOD(error) (status, __FILE__, __LINE__, msg, Common) + +/* Check a pointer and return if null. Set status to invalid, unless the + * status is already "out of memory" */ +#define RETURN_IF_NULL(A,result) \ +{ \ + if ((A) == NULL) \ + { \ + if (Common->status != CHOLMOD_OUT_OF_MEMORY) \ + { \ + ERROR (CHOLMOD_INVALID, "argument missing") ; \ + } \ + return (result) ; \ + } \ +} + +/* Return if Common is NULL or invalid */ +#define RETURN_IF_NULL_COMMON(result) \ +{ \ + if (Common == NULL) \ + { \ + return (result) ; \ + } \ + if (Common->itype != ITYPE || Common->dtype != DTYPE) \ + { \ + Common->status = CHOLMOD_INVALID ; \ + return (result) ; \ + } \ +} + +#define IS_NAN(x) CHOLMOD_IS_NAN(x) +#define IS_ZERO(x) CHOLMOD_IS_ZERO(x) +#define IS_NONZERO(x) CHOLMOD_IS_NONZERO(x) +#define IS_LT_ZERO(x) CHOLMOD_IS_LT_ZERO(x) +#define IS_GT_ZERO(x) CHOLMOD_IS_GT_ZERO(x) +#define IS_LE_ZERO(x) CHOLMOD_IS_LE_ZERO(x) + +/* 1e308 is a huge number that doesn't take many characters to print in a + * file, in CHOLMOD/Check/cholmod_read and _write. Numbers larger than this + * are interpretted as Inf, since sscanf doesn't read in Inf's properly. + * This assumes IEEE double precision arithmetic. DBL_MAX would be a little + * better, except that it takes too many digits to print in a file. */ +#define HUGE_DOUBLE 1e308 + +/* ========================================================================== */ +/* === int/UF_long and double/float definitions ============================= */ +/* ========================================================================== */ + +/* CHOLMOD is designed for 3 types of integer variables: + * + * (1) all integers are int + * (2) most integers are int, some are UF_long + * (3) all integers are UF_long + * + * and two kinds of floating-point values: + * + * (1) double + * (2) float + * + * the complex types (ANSI-compatible complex, and MATLAB-compatable zomplex) + * are based on the double or float type, and are not selected here. They + * are typically selected via template routines. + * + * This gives 6 different modes in which CHOLMOD can be compiled (only the + * first two are currently supported): + * + * DINT double, int prefix: cholmod_ + * DLONG double, UF_long prefix: cholmod_l_ + * DMIX double, mixed int/UF_long prefix: cholmod_m_ + * SINT float, int prefix: cholmod_si_ + * SLONG float, UF_long prefix: cholmod_sl_ + * SMIX float, mixed int/log prefix: cholmod_sm_ + * + * These are selected with compile time flags (-DDLONG, for example). If no + * flag is selected, the default is DINT. + * + * All six versions use the same include files. The user-visible include files + * are completely independent of which int/UF_long/double/float version is being + * used. The integer / real types in all data structures (sparse, triplet, + * dense, common, and triplet) are defined at run-time, not compile-time, so + * there is only one "cholmod_sparse" data type. Void pointers are used inside + * that data structure to point to arrays of the proper type. Each data + * structure has an itype and dtype field which determines the kind of basic + * types used. These are defined in Include/cholmod_core.h. + * + * FUTURE WORK: support all six types (float, and mixed int/UF_long) + * + * UF_long is normally defined as long. However, for WIN64 it is __int64. + * It can also be redefined for other platforms, by modifying UFconfig.h. + */ + +#include "UFconfig.h" + +/* -------------------------------------------------------------------------- */ +/* Size_max: the largest value of size_t */ +/* -------------------------------------------------------------------------- */ + +#define Size_max ((size_t) (-1)) + +/* routines for doing arithmetic on size_t, and checking for overflow */ +size_t cholmod_add_size_t (size_t a, size_t b, int *ok) ; +size_t cholmod_mult_size_t (size_t a, size_t k, int *ok) ; +size_t cholmod_l_add_size_t (size_t a, size_t b, int *ok) ; +size_t cholmod_l_mult_size_t (size_t a, size_t k, int *ok) ; + +/* -------------------------------------------------------------------------- */ +/* double (also complex double), UF_long */ +/* -------------------------------------------------------------------------- */ + +#ifdef DLONG +#define Real double +#define Int UF_long +#define Int_max UF_long_max +#define CHOLMOD(name) cholmod_l_ ## name +#define LONG +#define DOUBLE +#define ITYPE CHOLMOD_LONG +#define DTYPE CHOLMOD_DOUBLE +#define ID UF_long_id + +/* -------------------------------------------------------------------------- */ +/* double, int/UF_long */ +/* -------------------------------------------------------------------------- */ + +#elif defined (DMIX) +#error "mixed int/UF_long not yet supported" + +/* -------------------------------------------------------------------------- */ +/* single, int */ +/* -------------------------------------------------------------------------- */ + +#elif defined (SINT) +#error "single-precision not yet supported" + +/* -------------------------------------------------------------------------- */ +/* single, UF_long */ +/* -------------------------------------------------------------------------- */ + +#elif defined (SLONG) +#error "single-precision not yet supported" + +/* -------------------------------------------------------------------------- */ +/* single, int/UF_long */ +/* -------------------------------------------------------------------------- */ + +#elif defined (SMIX) +#error "single-precision not yet supported" + +/* -------------------------------------------------------------------------- */ +/* double (also complex double), int: this is the default */ +/* -------------------------------------------------------------------------- */ + +#else + +#ifndef DINT +#define DINT +#endif +#define INT +#define DOUBLE + +#define Real double +#define Int int +#define Int_max INT_MAX +#define CHOLMOD(name) cholmod_ ## name +#define ITYPE CHOLMOD_INT +#define DTYPE CHOLMOD_DOUBLE +#define ID "%d" + +#endif + + +/* ========================================================================== */ +/* === real/complex arithmetic ============================================== */ +/* ========================================================================== */ + +//#include "cholmod_complexity.h" + +/* ========================================================================== */ +/* === Architecture and BLAS ================================================ */ +/* ========================================================================== */ + +#define BLAS_OK Common->blas_ok +#include "cholmod_blas.h" + +/* ========================================================================== */ +/* === debugging definitions ================================================ */ +/* ========================================================================== */ + +#ifndef NDEBUG + +#include +#include "cholmod.h" + +/* The cholmod_dump routines are in the Check module. No CHOLMOD routine + * calls the cholmod_check_* or cholmod_print_* routines in the Check module, + * since they use Common workspace that may already be in use. Instead, they + * use the cholmod_dump_* routines defined there, which allocate their own + * workspace if they need it. */ + +#ifndef EXTERN +#define EXTERN extern +#endif + +/* double, int */ +EXTERN int cholmod_dump ; +EXTERN int cholmod_dump_malloc ; +UF_long cholmod_dump_sparse (cholmod_sparse *, const char *, cholmod_common *); +int cholmod_dump_factor (cholmod_factor *, const char *, cholmod_common *) ; +int cholmod_dump_triplet (cholmod_triplet *, const char *, cholmod_common *) ; +int cholmod_dump_dense (cholmod_dense *, const char *, cholmod_common *) ; +int cholmod_dump_subset (int *, size_t, size_t, const char *, + cholmod_common *) ; +int cholmod_dump_perm (int *, size_t, size_t, const char *, cholmod_common *) ; +int cholmod_dump_parent (int *, size_t, const char *, cholmod_common *) ; +void cholmod_dump_init (const char *, cholmod_common *) ; +int cholmod_dump_mem (const char *, UF_long, cholmod_common *) ; +void cholmod_dump_real (const char *, Real *, UF_long, UF_long, int, int, + cholmod_common *) ; +void cholmod_dump_super (UF_long, int *, int *, int *, int *, double *, int, + cholmod_common *) ; +int cholmod_dump_partition (UF_long, int *, int *, int *, int *, UF_long, + cholmod_common *) ; +int cholmod_dump_work(int, int, UF_long, cholmod_common *) ; + +/* double, UF_long */ +EXTERN int cholmod_l_dump ; +EXTERN int cholmod_l_dump_malloc ; +UF_long cholmod_l_dump_sparse (cholmod_sparse *, const char *, + cholmod_common *) ; +int cholmod_l_dump_factor (cholmod_factor *, const char *, cholmod_common *) ; +int cholmod_l_dump_triplet (cholmod_triplet *, const char *, cholmod_common *); +int cholmod_l_dump_dense (cholmod_dense *, const char *, cholmod_common *) ; +int cholmod_l_dump_subset (UF_long *, size_t, size_t, const char *, + cholmod_common *) ; +int cholmod_l_dump_perm (UF_long *, size_t, size_t, const char *, + cholmod_common *) ; +int cholmod_l_dump_parent (UF_long *, size_t, const char *, cholmod_common *) ; +void cholmod_l_dump_init (const char *, cholmod_common *) ; +int cholmod_l_dump_mem (const char *, UF_long, cholmod_common *) ; +void cholmod_l_dump_real (const char *, Real *, UF_long, UF_long, int, int, + cholmod_common *) ; +void cholmod_l_dump_super (UF_long, UF_long *, UF_long *, UF_long *, UF_long *, + double *, int, cholmod_common *) ; +int cholmod_l_dump_partition (UF_long, UF_long *, UF_long *, UF_long *, + UF_long *, UF_long, cholmod_common *) ; +int cholmod_l_dump_work(int, int, UF_long, cholmod_common *) ; + +#define DEBUG_INIT(s,Common) { CHOLMOD(dump_init)(s, Common) ; } +#define ASSERT(expression) (assert (expression)) + +#define PRK(k,params) \ +{ \ + if (CHOLMOD(dump) >= (k) && Common->print_function != NULL) \ + { \ + (Common->print_function) params ; \ + } \ +} + +#define PRINT0(params) PRK (0, params) +#define PRINT1(params) PRK (1, params) +#define PRINT2(params) PRK (2, params) +#define PRINT3(params) PRK (3, params) + +#define PRINTM(params) \ +{ \ + if (CHOLMOD(dump_malloc) > 0) \ + { \ + printf params ; \ + } \ +} + +#define DEBUG(statement) statement + +#else + +/* Debugging disabled (the normal case) */ +#define PRK(k,params) +#define DEBUG_INIT(s,Common) +#define PRINT0(params) +#define PRINT1(params) +#define PRINT2(params) +#define PRINT3(params) +#define PRINTM(params) +#define ASSERT(expression) +#define DEBUG(statement) +#endif + +#endif diff --git a/spqr_mini/cholmod_memory.c b/spqr_mini/cholmod_memory.c new file mode 100644 index 000000000..92f9f8ef9 --- /dev/null +++ b/spqr_mini/cholmod_memory.c @@ -0,0 +1,563 @@ +/* ========================================================================== */ +/* === Core/cholmod_memory ================================================== */ +/* ========================================================================== */ + +/* ----------------------------------------------------------------------------- + * CHOLMOD/Core Module. Copyright (C) 2005-2006, + * Univ. of Florida. Author: Timothy A. Davis + * The CHOLMOD/Core Module is licensed under Version 2.1 of the GNU + * Lesser General Public License. See lesser.txt for a text of the license. + * CHOLMOD is also available under other licenses; contact authors for details. + * http://www.cise.ufl.edu/research/sparse + * -------------------------------------------------------------------------- */ + +/* Core memory management routines: + * + * Primary routines: + * ----------------- + * cholmod_malloc malloc wrapper + * cholmod_free free wrapper + * + * Secondary routines: + * ------------------- + * cholmod_calloc calloc wrapper + * cholmod_realloc realloc wrapper + * cholmod_realloc_multiple realloc wrapper for multiple objects + * + * The user may make use of these, just like malloc and free. You can even + * malloc an object and safely free it with cholmod_free, and visa versa + * (except that the memory usage statistics will be corrupted). These routines + * do differ from malloc and free. If cholmod_free is given a NULL pointer, + * for example, it does nothing (unlike the ANSI free). cholmod_realloc does + * not return NULL if given a non-NULL pointer and a nonzero size, even if it + * fails (it sets an error code in Common->status instead). + * + * CHOLMOD keeps track of the amount of memory it has allocated, and so the + * cholmod_free routine includes as a parameter the size of the object being + * freed. This is only used for memory usage statistics, which are very useful + * in finding memory leaks in your program. If you, the user of CHOLMOD, pass + * the wrong size, the only consequence is that the memory usage statistics + * will be invalid. This will causes assertions to fail if CHOLMOD is + * compiled with debugging enabled, but otherwise it will cause no errors. + * + * The cholmod_free_* routines for each CHOLMOD object keep track of the size + * of the blocks they free, so they do not require you to pass their sizes + * as a parameter. + * + * If a block of size zero is requested, these routines allocate a block of + * size one instead. + */ + +#include "cholmod_internal.h" +#include "cholmod_core.h" + +/* ========================================================================== */ +/* === cholmod_add_size_t =================================================== */ +/* ========================================================================== */ + +/* Safely compute a+b, and check for integer overflow. If overflow occurs, + * return 0 and set OK to FALSE. Also return 0 if OK is FALSE on input. */ + +size_t CHOLMOD(add_size_t) (size_t a, size_t b, int *ok) +{ + size_t s = a + b ; + (*ok) = (*ok) && (s >= a) ; + return ((*ok) ? s : 0) ; +} + +/* ========================================================================== */ +/* === cholmod_mult_size_t ================================================== */ +/* ========================================================================== */ + +/* Safely compute a*k, where k should be small, and check for integer overflow. + * If overflow occurs, return 0 and set OK to FALSE. Also return 0 if OK is + * FALSE on input. */ + +size_t CHOLMOD(mult_size_t) (size_t a, size_t k, int *ok) +{ + size_t p = 0, s ; + while (*ok) + { + if (k % 2) + { + p = p + a ; + (*ok) = (*ok) && (p >= a) ; + } + k = k / 2 ; + if (!k) return (p) ; + s = a + a ; + (*ok) = (*ok) && (s >= a) ; + a = s ; + } + return (0) ; +} + + +/* ========================================================================== */ +/* === cholmod_malloc ======================================================= */ +/* ========================================================================== */ + +/* Wrapper around malloc routine. Allocates space of size MAX(1,n)*size, where + * size is normally a sizeof (...). + * + * This routine, cholmod_calloc, and cholmod_realloc do not set Common->status + * to CHOLMOD_OK on success, so that a sequence of cholmod_malloc's, _calloc's, + * or _realloc's can be used. If any of them fails, the Common->status will + * hold the most recent error status. + * + * Usage, for a pointer to int: + * + * p = cholmod_malloc (n, sizeof (int), Common) + * + * Uses a pointer to the malloc routine (or its equivalent) defined in Common. + */ + +void *CHOLMOD(malloc) /* returns pointer to the newly malloc'd block */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* --------------- */ + cholmod_common *Common +) +{ + void *p ; + size_t s ; + int ok = TRUE ; + + RETURN_IF_NULL_COMMON (NULL) ; + if (size == 0) + { + ERROR (CHOLMOD_INVALID, "sizeof(item) must be > 0") ; + p = NULL ; + } + else if (n >= (Size_max / size) || n >= Int_max) + { + /* object is too big to allocate without causing integer overflow */ + ERROR (CHOLMOD_TOO_LARGE, "problem too large") ; + p = NULL ; + } + else + { + /* call malloc, or its equivalent */ + s = CHOLMOD(mult_size_t) (MAX (1,n), size, &ok) ; + p = ok ? ((Common->malloc_memory) (s)) : NULL ; + if (p == NULL) + { + /* failure: out of memory */ + ERROR (CHOLMOD_OUT_OF_MEMORY, "out of memory") ; + } + else + { + /* success: increment the count of objects allocated */ + Common->malloc_count++ ; + Common->memory_inuse += (n * size) ; + Common->memory_usage = + MAX (Common->memory_usage, Common->memory_inuse) ; + PRINTM (("cholmod_malloc %p %d cnt: %d inuse %d\n", + p, n*size, Common->malloc_count, Common->memory_inuse)) ; + } + } + return (p) ; +} + + +/* ========================================================================== */ +/* === cholmod_free ========================================================= */ +/* ========================================================================== */ + +/* Wrapper around free routine. Returns NULL, which can be assigned to the + * pointer being freed, as in: + * + * p = cholmod_free (n, sizeof (int), p, Common) ; + * + * In CHOLMOD, the syntax: + * + * cholmod_free (n, sizeof (int), p, Common) ; + * + * is used if p is a local pointer and the routine is returning shortly. + * Uses a pointer to the free routine (or its equivalent) defined in Common. + * Nothing is freed if the pointer is NULL. + */ + +void *CHOLMOD(free) /* always returns NULL */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* ---- in/out --- */ + void *p, /* block of memory to free */ + /* --------------- */ + cholmod_common *Common +) +{ + RETURN_IF_NULL_COMMON (NULL) ; + if (p != NULL) + { + /* only free the object if the pointer is not NULL */ + /* call free, or its equivalent */ + (Common->free_memory) (p) ; + Common->malloc_count-- ; + Common->memory_inuse -= (n * size) ; + PRINTM (("cholmod_free %p %d cnt: %d inuse %d\n", + p, n*size, Common->malloc_count, Common->memory_inuse)) ; + /* This assertion will fail if the user calls cholmod_malloc and + * cholmod_free with mismatched memory sizes. It shouldn't fail + * otherwise. */ + ASSERT (IMPLIES (Common->malloc_count == 0, Common->memory_inuse == 0)); + } + /* return NULL, and the caller should assign this to p. This avoids + * freeing the same pointer twice. */ + return (NULL) ; +} + + +/* ========================================================================== */ +/* === cholmod_calloc ======================================================= */ +/* ========================================================================== */ + +/* Wrapper around calloc routine. + * + * Uses a pointer to the calloc routine (or its equivalent) defined in Common. + * This routine is identical to malloc, except that it zeros the newly allocated + * block to zero. + */ + +void *CHOLMOD(calloc) /* returns pointer to the newly calloc'd block */ +( + /* ---- input ---- */ + size_t n, /* number of items */ + size_t size, /* size of each item */ + /* --------------- */ + cholmod_common *Common +) +{ + void *p ; + + RETURN_IF_NULL_COMMON (NULL) ; + if (size == 0) + { + ERROR (CHOLMOD_INVALID, "sizeof(item) must be > 0") ; + p = NULL ; + } + else if (n >= (Size_max / size) || n >= Int_max) + { + /* object is too big to allocate without causing integer overflow */ + ERROR (CHOLMOD_TOO_LARGE, "problem too large") ; + p = NULL ; + } + else + { + /* call calloc, or its equivalent */ + p = (Common->calloc_memory) (MAX (1,n), size) ; + if (p == NULL) + { + /* failure: out of memory */ + ERROR (CHOLMOD_OUT_OF_MEMORY, "out of memory") ; + } + else + { + /* success: increment the count of objects allocated */ + Common->malloc_count++ ; + Common->memory_inuse += (n * size) ; + Common->memory_usage = + MAX (Common->memory_usage, Common->memory_inuse) ; + PRINTM (("cholmod_malloc %p %d cnt: %d inuse %d\n", + p, n*size, Common->malloc_count, Common->memory_inuse)) ; + } + } + return (p) ; +} + + +/* ========================================================================== */ +/* === cholmod_realloc ====================================================== */ +/* ========================================================================== */ + +/* Wrapper around realloc routine. Given a pointer p to a block of size + * (*n)*size memory, it changes the size of the block pointed to by p to be + * MAX(1,nnew)*size in size. It may return a pointer different than p. This + * should be used as (for a pointer to int): + * + * p = cholmod_realloc (nnew, sizeof (int), p, *n, Common) ; + * + * If p is NULL, this is the same as p = cholmod_malloc (...). + * A size of nnew=0 is treated as nnew=1. + * + * If the realloc fails, p is returned unchanged and Common->status is set + * to CHOLMOD_OUT_OF_MEMORY. If successful, Common->status is not modified, + * and p is returned (possibly changed) and pointing to a large block of memory. + * + * Uses a pointer to the realloc routine (or its equivalent) defined in Common. + */ + +void *CHOLMOD(realloc) /* returns pointer to reallocated block */ +( + /* ---- input ---- */ + size_t nnew, /* requested # of items in reallocated block */ + size_t size, /* size of each item */ + /* ---- in/out --- */ + void *p, /* block of memory to realloc */ + size_t *n, /* current size on input, nnew on output if successful*/ + /* --------------- */ + cholmod_common *Common +) +{ + size_t nold = (*n) ; + void *pnew ; + size_t s ; + int ok = TRUE ; + + RETURN_IF_NULL_COMMON (NULL) ; + if (size == 0) + { + ERROR (CHOLMOD_INVALID, "sizeof(item) must be > 0") ; + p = NULL ; + } + else if (p == NULL) + { + /* A fresh object is being allocated. */ + PRINT1 (("realloc fresh: %d %d\n", nnew, size)) ; + p = CHOLMOD(malloc) (nnew, size, Common) ; + *n = (p == NULL) ? 0 : nnew ; + } + else if (nold == nnew) + { + /* Nothing to do. Do not change p or n. */ + PRINT1 (("realloc nothing: %d %d\n", nnew, size)) ; + } + else if (nnew >= (Size_max / size) || nnew >= Int_max) + { + /* failure: nnew is too big. Do not change p or n. */ + ERROR (CHOLMOD_TOO_LARGE, "problem too large") ; + } + else + { + /* The object exists, and is changing to some other nonzero size. */ + /* call realloc, or its equivalent */ + PRINT1 (("realloc : %d to %d, %d\n", nold, nnew, size)) ; + pnew = NULL ; + + s = CHOLMOD(mult_size_t) (MAX (1,nnew), size, &ok) ; + pnew = ok ? ((Common->realloc_memory) (p, s)) : NULL ; + + if (pnew == NULL) + { + /* Do not change p, since it still points to allocated memory */ + if (nnew <= nold) + { + /* The attempt to reduce the size of the block from n to + * nnew has failed. The current block is not modified, so + * pretend to succeed, but do not change p. Do change + * CHOLMOD's notion of the size of the block, however. */ + *n = nnew ; + PRINTM (("nnew <= nold failed, pretend to succeed\n")) ; + PRINTM (("cholmod_free %p %d cnt: %d inuse %d\n" + "cholmod_malloc %p %d cnt: %d inuse %d\n", + p, nold*size, Common->malloc_count-1, + Common->memory_inuse - nold*size, + p, nnew*size, Common->malloc_count, + Common->memory_inuse + (nnew-nold)*size)) ; + Common->memory_inuse += ((nnew-nold) * size) ; + } + else + { + /* Increasing the size of the block has failed. + * Do not change n. */ + ERROR (CHOLMOD_OUT_OF_MEMORY, "out of memory") ; + } + } + else + { + /* success: return revised p and change the size of the block */ + PRINTM (("cholmod_free %p %d cnt: %d inuse %d\n" + "cholmod_malloc %p %d cnt: %d inuse %d\n", + p, nold*size, Common->malloc_count-1, + Common->memory_inuse - nold*size, + pnew, nnew*size, Common->malloc_count, + Common->memory_inuse + (nnew-nold)*size)) ; + p = pnew ; + *n = nnew ; + Common->memory_inuse += ((nnew-nold) * size) ; + } + Common->memory_usage = MAX (Common->memory_usage, Common->memory_inuse); + } + + return (p) ; +} + + +/* ========================================================================== */ +/* === cholmod_realloc_multiple ============================================= */ +/* ========================================================================== */ + +/* reallocate multiple blocks of memory, all of the same size (up to two integer + * and two real blocks). Either reallocations all succeed, or all are returned + * in the original size (they are freed if the original size is zero). The nnew + * blocks are of size 1 or more. + */ + +int CHOLMOD(realloc_multiple) +( + /* ---- input ---- */ + size_t nnew, /* requested # of items in reallocated blocks */ + int nint, /* number of int/UF_long blocks */ + int xtype, /* CHOLMOD_PATTERN, _REAL, _COMPLEX, or _ZOMPLEX */ + /* ---- in/out --- */ + void **I, /* int or UF_long block */ + void **J, /* int or UF_long block */ + void **X, /* complex or double block */ + void **Z, /* zomplex case only: double block */ + size_t *nold_p, /* current size of the I,J,X,Z blocks on input, + * nnew on output if successful */ + /* --------------- */ + cholmod_common *Common +) +{ + double *xx, *zz ; + size_t i, j, x, z, nold ; + + RETURN_IF_NULL_COMMON (FALSE) ; + + if (xtype < CHOLMOD_PATTERN || xtype > CHOLMOD_ZOMPLEX) + { + ERROR (CHOLMOD_INVALID, "invalid xtype") ; + return (FALSE) ; + } + + nold = *nold_p ; + + if (nint < 1 && xtype == CHOLMOD_PATTERN) + { + /* nothing to do */ + return (TRUE) ; + } + + i = nold ; + j = nold ; + x = nold ; + z = nold ; + + if (nint > 0) + { + *I = CHOLMOD(realloc) (nnew, sizeof (Int), *I, &i, Common) ; + } + if (nint > 1) + { + *J = CHOLMOD(realloc) (nnew, sizeof (Int), *J, &j, Common) ; + } + + switch (xtype) + { + case CHOLMOD_REAL: + *X = CHOLMOD(realloc) (nnew, sizeof (double), *X, &x, Common) ; + break ; + + case CHOLMOD_COMPLEX: + *X = CHOLMOD(realloc) (nnew, 2*sizeof (double), *X, &x, Common) ; + break ; + + case CHOLMOD_ZOMPLEX: + *X = CHOLMOD(realloc) (nnew, sizeof (double), *X, &x, Common) ; + *Z = CHOLMOD(realloc) (nnew, sizeof (double), *Z, &z, Common) ; + break ; + } + + if (Common->status < CHOLMOD_OK) + { + /* one or more realloc's failed. Resize all back down to nold. */ + + if (nold == 0) + { + + if (nint > 0) + { + *I = CHOLMOD(free) (i, sizeof (Int), *I, Common) ; + } + if (nint > 1) + { + *J = CHOLMOD(free) (j, sizeof (Int), *J, Common) ; + } + + switch (xtype) + { + case CHOLMOD_REAL: + *X = CHOLMOD(free) (x, sizeof (double), *X, Common) ; + break ; + + case CHOLMOD_COMPLEX: + *X = CHOLMOD(free) (x, 2*sizeof (double), *X, Common) ; + break ; + + case CHOLMOD_ZOMPLEX: + *X = CHOLMOD(free) (x, sizeof (double), *X, Common) ; + *Z = CHOLMOD(free) (x, sizeof (double), *Z, Common) ; + break ; + } + + } + else + { + if (nint > 0) + { + *I = CHOLMOD(realloc) (nold, sizeof (Int), *I, &i, Common) ; + } + if (nint > 1) + { + *J = CHOLMOD(realloc) (nold, sizeof (Int), *J, &j, Common) ; + } + + switch (xtype) + { + case CHOLMOD_REAL: + *X = CHOLMOD(realloc) (nold, sizeof (double), *X, &x, + Common) ; + break ; + + case CHOLMOD_COMPLEX: + *X = CHOLMOD(realloc) (nold, 2*sizeof (double), *X, &x, + Common) ; + break ; + + case CHOLMOD_ZOMPLEX: + *X = CHOLMOD(realloc) (nold, sizeof (double), *X, &x, + Common) ; + *Z = CHOLMOD(realloc) (nold, sizeof (double), *Z, &z, + Common) ; + break ; + } + + } + + return (FALSE) ; + } + + if (nold == 0) + { + /* New space was allocated. Clear the first entry so that valgrind + * doesn't complain about its access in change_complexity + * (Core/cholmod_complex.c). */ + xx = *X ; + zz = *Z ; + switch (xtype) + { + case CHOLMOD_REAL: + xx [0] = 0 ; + break ; + + case CHOLMOD_COMPLEX: + xx [0] = 0 ; + xx [1] = 0 ; + break ; + + case CHOLMOD_ZOMPLEX: + xx [0] = 0 ; + zz [0] = 0 ; + break ; + } + } + + /* all realloc's succeeded, change size to reflect realloc'ed size. */ + *nold_p = nnew ; + return (TRUE) ; +} diff --git a/spqr_mini/spqr_front.cpp b/spqr_mini/spqr_front.cpp new file mode 100644 index 000000000..1bd16ed67 --- /dev/null +++ b/spqr_mini/spqr_front.cpp @@ -0,0 +1,664 @@ +// ============================================================================= +// === spqr_front ============================================================== +// ============================================================================= + +/* Given an m-by-n frontal matrix, use Householder reflections to reduce it + to upper trapezoidal form. Columns 0:npiv-1 are checked against tol. + + 0 # x x x x x x + 1 # x x x x x x + 2 # x x x x x x + 3 # x x x x x x + 4 - # x x x x x <- Stair [0] = 4 + 5 # x x x x x + 6 # x x x x x + 7 # x x x x x + 8 - # x x x x <- Stair [1] = 8 + 9 # x x x x + 10 # x x x x + 11 # x x x x + 12 - # x x x <- Stair [2] = 12 + 13 # x x x + 14 - # x x <- Stair [3] = 14 + 15 - # x <- Stair [4] = 15 + 16 - # <- Stair [5] = 16 + - <- Stair [6] = 17 + + Suppose npiv = 3, and no columns fall below tol: + + 0 R r r r r r r + 1 h R r r r r r + 2 h h R r r r r + 3 h h h C c c c + 4 - h h h C c c <- Stair [0] = 4 + 5 h h h h C c + 6 h h h h h C + 7 h h h h h h + 8 - h h h h h <- Stair [1] = 8 + 9 h h h h h + 10 h h h h h + 11 h h h h h + 12 - h h h h <- Stair [2] = 12 + 13 h h h h + 14 - h h h <- Stair [3] = 14 + 15 - h h <- Stair [4] = 15 + 16 - h <- Stair [5] = 16 + - <- Stair [6] = 17 + + where r is an entry in the R block, c is an entry in the C (contribution) + block, and h is an entry in the H block (Householder vectors). Diagonal + entries are capitalized. + + Suppose the 2nd column has a norm <= tol; the result is a "squeezed" R: + + 0 R r r r r r r <- Stair [1] = 0 to denote a dead pivot column + 1 h - R r r r r + 2 h - h C c c c + 3 h - h h C c c + 4 - - h h h C c <- Stair [0] = 4 + 5 - h h h h C + 6 - h h h h h + 7 - h h h h h + 8 - h h h h h + 9 h h h h h + 10 h h h h h + 11 h h h h h + 12 - h h h h <- Stair [2] = 12 + 13 h h h h + 14 - h h h <- Stair [3] = 14 + 15 - h h <- Stair [4] = 15 + 16 - h <- Stair [5] = 16 + - <- Stair [6] = 17 + + where "diagonal" entries are capitalized. The 2nd H vector is missing + (it is H2 = I, identity). The 2nd column of R is not deleted. The + contribution block is always triangular, but the first npiv columns of + the R can become "staggered". Columns npiv to n-1 in the R block are + always the same length. + + If columns are found "dead", the staircase may be updated. Stair[k] is + set to zero if k is dead. Also, Stair[k] is increased, if necessary, to + ensure that R and C reside within the staircase. For example: + + 0 0 0 + 0 0 x + + with npiv = 2 has a Stair = [ 0 1 2 ] on output, to reflect the C block: + + - C c + - - C + + A tol of zero means that any nonzero norm (however small) is accepted; + only exact zero columns are flagged as dead. A negative tol means that + the norms are ignored; a column is never flagged dead. The default tol + is set elsewhere as 20 * (m+1) * eps * max column 2-norm of A. + + LAPACK's dlarf* routines are used to construct and apply the Householder + reflections. The panel size (block size) is provided as an input + parameter, which defines the number of Householder vectors in a panel. + However, when the front is small (or when the remaining part + of a front is small) the block size is increased to include the entire + front. "Small" is defined, below, as fronts with fewer than 5000 entries. + + NOTE: this function does not check its inputs. If the caller runs out of + memory and passes NULL pointers, this function will segfault. +*/ + +#include "spqr_subset.hpp" +#include "iostream" + +#define SMALL 5000 +#define MINCHUNK 4 +#define MINCHUNK_RATIO 4 + +// ============================================================================= +// === spqr_private_house ====================================================== +// ============================================================================= + +// Construct a Householder reflection H = I - tau * v * v' such that H*x is +// reduced to zero except for the first element. Returns X [0] = the first +// entry of H*x, and X [1:n-1] = the Householder vector V [1:n-1], where +// V [0] = 1. If X [1:n-1] is zero, then the H=I (tau = 0) is returned, +// and V [1:n-1] is all zero. In MATLAB (1-based indexing), ignoring the +// rescaling done in dlarfg/zlarfg, this function computes the following: + +/* + function [x, tau] = house (x) + n = length (x) ; + beta = norm (x) ; + if (x (1) > 0) + beta = -beta ; + end + tau = (beta - x (1)) / beta ; + x (2:n) = x (2:n) / (x (1) - beta) ; + x (1) = beta ; +*/ + +// Note that for the complex case, the reflection must be applied as H'*x, +// which requires that tau be conjugated in spqr_private_apply1. +// +// This function performs about 3*n+2 flops + +inline double spqr_private_larfg (Int n, double *X, cholmod_common *cc) +{ + double tau = 0 ; + BLAS_INT N = n, one = 1 ; + if (CHECK_BLAS_INT && !EQ (N,n)) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_DLARFG (&N, X, X + 1, &one, &tau) ; + } + return (tau) ; +} + + +inline Complex spqr_private_larfg (Int n, Complex *X, cholmod_common *cc) +{ + Complex tau = 0 ; + BLAS_INT N = n, one = 1 ; + if (CHECK_BLAS_INT && !EQ (N,n)) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_ZLARFG (&N, X, X + 1, &one, &tau) ; + } + return (tau) ; +} + + +template Entry spqr_private_house // returns tau +( + // inputs, not modified + Int n, + + // input/output + Entry *X, // size n + + cholmod_common *cc +) +{ + return (spqr_private_larfg (n, X, cc)) ; +} + + +// ============================================================================= +// === spqr_private_apply1 ===================================================== +// ============================================================================= + +// Apply a single Householder reflection; C = C - tau * v * v' * C. The +// algorithm used by dlarf is: + +/* + function C = apply1 (C, v, tau) + w = C'*v ; + C = C - tau*v*w' ; +*/ + +// For the complex case, we need to apply H', which requires that tau be +// conjugated. +// +// If applied to a single column, this function performs 2*n-1 flops to +// compute w, and 2*n+1 to apply it to C, for a total of 4*n flops. + +inline void spqr_private_larf (Int m, Int n, double *V, double tau, + double *C, Int ldc, double *W, cholmod_common *cc) +{ + BLAS_INT M = m, N = n, LDC = ldc, one = 1 ; + char left = 'L' ; + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDC,ldc))) + { + cc->blas_ok = FALSE ; + + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_DLARF (&left, &M, &N, V, &one, &tau, C, &LDC, W) ; + } +} + +inline void spqr_private_larf (Int m, Int n, Complex *V, Complex tau, + Complex *C, Int ldc, Complex *W, cholmod_common *cc) +{ + BLAS_INT M = m, N = n, LDC = ldc, one = 1 ; + char left = 'L' ; + Complex conj_tau = spqr_conj (tau) ; + if (CHECK_BLAS_INT && !(EQ (M,m) && EQ (N,n) && EQ (LDC,ldc))) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_ZLARF (&left, &M, &N, V, &one, &conj_tau, C, &LDC, W) ; + } +} + + +template void spqr_private_apply1 +( + // inputs, not modified + Int m, // C is m-by-n + Int n, + Int ldc, // leading dimension of C + Entry *V, // size m, Householder vector V + Entry tau, // Householder coefficient + + // input/output + Entry *C, // size m-by-n + + // workspace, not defined on input or output + Entry *W, // size n + + cholmod_common *cc +) +{ + Entry vsave ; + if (m <= 0 || n <= 0) + { + return ; // nothing to do + } + vsave = V [0] ; // temporarily restore unit diagonal of V + V [0] = 1 ; + spqr_private_larf (m, n, V, tau, C, ldc, W, cc) ; + V [0] = vsave ; // restore V [0] +} + + +// ============================================================================= +// === spqr_front ============================================================== +// ============================================================================= + +// Factorize a front F into a sequence of Householder vectors H, and an upper +// trapezoidal matrix R. R may be a squeezed upper trapezoidal matrix if any +// of the leading npiv columns are linearly dependent. Returns the row index +// rank that indicates the first entry in C, which is F (rank,npiv), or 0 +// on error. + +template Int spqr_front +( + // input, not modified + Int m, // F is m-by-n with leading dimension m + Int n, + Int npiv, // number of pivot columns + double tol, // a column is flagged as dead if its norm is <= tol + Int ntol, // apply tol only to first ntol pivot columns + Int fchunk, // block size for compact WY Householder reflections, + // treated as 1 if fchunk <= 1 + + // input/output + Entry *F, // frontal matrix F of size m-by-n + Int *Stair, // size n, entries F (Stair[k]:m-1, k) are all zero, + // for each k = 0:n-1, and remain zero on output. + char *Rdead, // size npiv; all zero on input. If k is dead, + // Rdead [k] is set to 1 + + // output, not defined on input + Entry *Tau, // size n, Householder coefficients + + // workspace, undefined on input and output + Entry *W, // size b*n, where b = min (fchunk,n,m) + + // input/output + double *wscale, + double *wssq, + + cholmod_common *cc // for cc->hypotenuse function +) +{ +// std::cout << "**************spqr_front dumping started****************" << std::endl; +// std::cout << "m: " << m << " n: " << n << " npiv: " << npiv << " tol: " << tol +// << " ntol: " << ntol << " fchunk: " << fchunk << std::endl; +// for (int i=0; i= 0 && n >= 0) ; + + npiv = MAX (0, npiv) ; // npiv must be between 0 and n + npiv = MIN (n, npiv) ; + + g1 = 0 ; // row index of first queued-up Householder + k1 = 0 ; // pending Householders are in F (g1:t, k1:k2-1) + k2 = 0 ; + V = F ; // Householder vectors start here + g = 0 ; // number of good Householders found + nv = 0 ; // number of Householder reflections queued up + vzeros = 0 ; // number of explicit zeros in queued-up H's + t = 0 ; // staircase of current column + fchunk = MAX (fchunk, 1) ; + minchunk = MAX (MINCHUNK, fchunk/MINCHUNK_RATIO) ; + rank = MIN (m,npiv) ; // F (rank,npiv) is the first entry in C. rank + // is also the number of rows in the R block, + // and the number of good pivot columns found. + + ntol = MIN (ntol, npiv) ; // Note ntol can be negative, which means to + // not use tol at all. + + PR (("Front %ld by %ld with %ld pivots\n", m, n, npiv)) ; + for (k = 0 ; k < n ; k++) + { + + // --------------------------------------------------------------------- + // reduce the kth column of F to eliminate all but "diagonal" F (g,k) + // --------------------------------------------------------------------- + + // get the staircase for the kth column, and operate on the "diagonal" + // F (g,k); eliminate F (g+1:t-1, k) to zero + t0 = t ; // t0 = staircase of column k-1 + t = Stair [k] ; // t = staircase of this column k + + PR (("k %ld g %ld m %ld n %ld npiv %ld\n", k, g, m, n, npiv)) ; + if (g >= m) + { + // F (g,k) is outside the matrix, so we're done. If this happens + // when k < npiv, then there is no contribution block. + PR (("hit the wall, npiv: %ld k %ld rank %ld\n", npiv, k, rank)) ; + for ( ; k < npiv ; k++) + { + Rdead [k] = 1 ; + Stair [k] = 0 ; // remaining pivot columns all dead + Tau [k] = 0 ; + } + for ( ; k < n ; k++) + { + Stair [k] = m ; // non-pivotal columns + Tau [k] = 0 ; + } + ASSERT (nv == 0) ; // there can be no pending updates + return (rank) ; + } + + // if t < g+1, then this column is all zero; fix staircase so that R is + // always inside the staircase. + t = MAX (g+1,t) ; + Stair [k] = t ; + + // --------------------------------------------------------------------- + // If t just grew a lot since the last t, apply H now to all of F + // --------------------------------------------------------------------- + + // vzeros is the number of zero entries in V after including the next + // Householder vector. If it would exceed 50% of the size of V, + // apply the pending Householder reflections now, but only if + // enough vectors have accumulated. + + vzeros += nv * (t - t0) ; + if (nv >= minchunk) + { + vsize = (nv*(nv+1))/2 + nv*(t-g1-nv) ; + if (vzeros > MAX (16, vsize/2)) + { + // apply pending block of Householder reflections + PR (("(1) apply k1 %ld k2 %ld\n", k1, k2)) ; + spqr_larftb ( + 0, // method 0: Left, Transpose + t0-g1, n-k2, nv, m, m, + V, // F (g1:t-1, k1:k1+nv-1) + &Tau [k1], // Tau (k1:k-1) + &F [INDEX (g1,k2,m)], // F (g1:t-1, k2:n-1) + W, cc) ; // size nv*nv + nv*(n-k2) + nv = 0 ; // clear queued-up Householder reflections + vzeros = 0 ; + } + } + + // --------------------------------------------------------------------- + // find a Householder reflection that reduces column k + // --------------------------------------------------------------------- + + tau = spqr_private_house (t-g, &F [INDEX (g,k,m)], cc) ; + + // --------------------------------------------------------------------- + // check to see if the kth column is OK + // --------------------------------------------------------------------- + + if (k < ntol && (wk = spqr_abs (F [INDEX (g,k,m)], cc)) <= tol) + { + // ----------------------------------------------------------------- + // norm (F (g:t-1, k)) is too tiny; the kth pivot column is dead + // ----------------------------------------------------------------- + + // keep track of the 2-norm of w, the dead column 2-norms + if (wk != 0) + { + // see also LAPACK's dnrm2 function + if ((*wscale) == 0) + { + // this is the nonzero first entry in w + (*wssq) = 1 ; + } + if ((*wscale) < wk) + { + double rr = (*wscale) / wk ; + (*wssq) = 1 + (*wssq) * rr * rr ; + (*wscale) = wk ; + } + else + { + double rr = wk / (*wscale) ; + (*wssq) += rr * rr ; + } + } + + // zero out F (g:m-1,k) and flag it as dead + for (i = g ; i < m ; i++) + { + // This is not strictly necessary. On output, entries outside + // the staircase are ignored. + F [INDEX (i,k,m)] = 0 ; + } + Stair [k] = 0 ; + Tau [k] = 0 ; + Rdead [k] = 1 ; + + if (nv > 0) + { + // apply pending block of Householder reflections + PR (("(2) apply k1 %ld k2 %ld\n", k1, k2)) ; + spqr_larftb ( + 0, // method 0: Left, Transpose + t0-g1, n-k2, nv, m, m, + V, // F (g1:t-1, k1:k1+nv-1) + &Tau [k1], // Tau (k1:k-1) + &F [INDEX (g1,k2,m)], // F (g1:t-1, k2:n-1) + W, cc) ; // size nv*nv + nv*(n-k2) + nv = 0 ; // clear queued-up Householder reflections + vzeros = 0 ; + } + + } + else + { + // ----------------------------------------------------------------- + // one more good pivot column found + // ----------------------------------------------------------------- + + Tau [k] = tau ; // save the Householder coefficient + if (nv == 0) + { + // start the queue of pending Householder updates, and define + // the current panel as k1:k2-1 + g1 = g ; // first row of V + k1 = k ; // first column of V + k2 = MIN (n, k+fchunk) ; // k2-1 is last col in panel + V = &F [INDEX (g1,k1,m)] ; // pending V starts here + + // check for switch to unblocked code + mleft = m-g1 ; // number of rows left + nleft = n-k1 ; // number of columns left + if (mleft * (nleft-(fchunk+4)) < SMALL || mleft <= fchunk/2 + || fchunk <= 1) + { + // remaining matrix is small; switch to unblocked code by + // including the rest of the matrix in the panel. Always + // use unblocked code if fchunk <= 1. + k2 = n ; + } + } + nv++ ; // one more pending update; V is F (g1:t-1, k1:k1+nv-1) + + // ----------------------------------------------------------------- + // keep track of "pure" flops, for performance testing only + // ----------------------------------------------------------------- + + // The Householder vector is of length t-g, including the unit + // diagonal, and takes 3*(t-g) flops to compute. It will be + // applied as a block, but compute the "pure" flops by assuming + // that this single Householder vector is computed and then applied + // just by itself to the rest of the frontal matrix (columns + // k+1:n-1, or n-k-1 columns). Applying the Householder reflection + // to just one column takes 4*(t-g) flops. This computation only + // works if TBB is disabled, merely because it uses a global + // variable to keep track of the flop count. If TBB is used, this + // computation may result in a race condition; it is disabled in + // that case. + + FLOP_COUNT ((t-g) * (3 + 4 * (n-k-1))) ; + + // ----------------------------------------------------------------- + // apply the kth Householder reflection to the current panel + // ----------------------------------------------------------------- + + // F (g:t-1, k+1:k2-1) -= v * tau * v' * F (g:t-1, k+1:k2-1), where + // v is stored in F (g:t-1,k). This applies just one reflection + // to the current panel. + PR (("apply 1: k %ld\n", k)) ; + spqr_private_apply1 (t-g, k2-k-1, m, &F [INDEX (g,k,m)], tau, + &F [INDEX (g,k+1,m)], W, cc) ; + + g++ ; // one more pivot found + + // ----------------------------------------------------------------- + // apply the Householder reflections if end of panel reached + // ----------------------------------------------------------------- + + if (k == k2-1 || g == m) // or if last pivot is found + { + // apply pending block of Householder reflections + PR (("(3) apply k1 %ld k2 %ld\n", k1, k2)) ; + spqr_larftb ( + 0, // method 0: Left, Transpose + t-g1, n-k2, nv, m, m, + V, // F (g1:t-1, k1:k1+nv-1) + &Tau [k1], // Tau (k1:k2-1) + &F [INDEX (g1,k2,m)], // F (g1:t-1, k2:n-1) + W, cc) ; // size nv*nv + nv*(n-k2) + nv = 0 ; // clear queued-up Householder reflections + vzeros = 0 ; + } + } + + // --------------------------------------------------------------------- + // determine the rank of the pivot columns + // --------------------------------------------------------------------- + + if (k == npiv-1) + { + // the rank is the number of good columns found in the first + // npiv columns. It is also the number of rows in the R block. + // F (rank,npiv) is first entry in the C block. + rank = g ; + PR (("rank of Front pivcols: %ld\n", rank)) ; + } + } + + if (CHECK_BLAS_INT && !cc->blas_ok) + { + // This cannot occur if the BLAS_INT and the Int are the same integer. + // In that case, CHECK_BLAS_INT is FALSE at compile-time, and the + // compiler will then remove this as dead code. + ERROR (CHOLMOD_INVALID, "problem too large for the BLAS") ; + return (0) ; + } + + return (rank) ; +} + + +// ============================================================================= + +template Int spqr_front +( + // input, not modified + Int m, // F is m-by-n with leading dimension m + Int n, + Int npiv, // number of pivot columns + double tol, // a column is flagged as dead if its norm is <= tol + Int ntol, // apply tol only to first ntol pivot columns + Int fchunk, // block size for compact WY Householder reflections, + // treated as 1 if fchunk <= 1 (in which case the + // unblocked code is used). + + // input/output + double *F, // frontal matrix F of size m-by-n + Int *Stair, // size n, entries F (Stair[k]:m-1, k) are all zero, + // and remain zero on output. + char *Rdead, // size npiv; all zero on input. If k is dead, + // Rdead [k] is set to 1 + + // output, not defined on input + double *Tau, // size n, Householder coefficients + + // workspace, undefined on input and output + double *W, // size b*n, where b = min (fchunk,n,m) + + // input/output + double *wscale, + double *wssq, + + cholmod_common *cc // for cc->hypotenuse function +) ; + +// ============================================================================= + +template Int spqr_front +( + // input, not modified + Int m, // F is m-by-n with leading dimension m + Int n, + Int npiv, // number of pivot columns + double tol, // a column is flagged as dead if its norm is <= tol + Int ntol, // apply tol only to first ntol pivot columns + Int fchunk, // block size for compact WY Householder reflections, + // treated as 1 if fchunk <= 1 (in which case the + // unblocked code is used). + + // input/output + Complex *F, // frontal matrix F of size m-by-n + Int *Stair, // size n, entries F (Stair[k]:m-1, k) are all zero, + // and remain zero on output. + char *Rdead, // size npiv; all zero on input. If k is dead, + // Rdead [k] is set to 1 + + // output, not defined on input + Complex *Tau, // size n, Householder coefficients + + // workspace, undefined on input and output + Complex *W, // size b*n, where b = min (fchunk,n,m) + + // input/output + double *wscale, + double *wssq, + + cholmod_common *cc // for cc->hypotenuse function +) ; diff --git a/spqr_mini/spqr_front.h b/spqr_mini/spqr_front.h new file mode 100644 index 000000000..e69de29bb diff --git a/spqr_mini/spqr_larftb.cpp b/spqr_mini/spqr_larftb.cpp new file mode 100644 index 000000000..3d7d9d713 --- /dev/null +++ b/spqr_mini/spqr_larftb.cpp @@ -0,0 +1,236 @@ +// ============================================================================= +// === spqr_larftb ============================================================= +// ============================================================================= + +// Apply a set of Householder reflections to a matrix. Given the vectors +// V and coefficients Tau, construct the matrix T and then apply the updates. +// In MATLAB (1-based indexing), this function computes the following: + +/* + function C = larftb (C, V, Tau, method) + [v k] = size (V) ; + [m n] = size (C) ; + % construct T for the compact WY representation + V = tril (V,-1) + eye (v,k) ; + T = zeros (k,k) ; + T (1,1) = Tau (1) ; + for j = 2:k + tau = Tau (j) ; + z = -tau * V (:, 1:j-1)' * V (:,j) ; + T (1:j-1,j) = T (1:j-1,1:j-1) * z ; + T (j,j) = tau ; + end + % apply the updates + if (method == 0) + C = C - V * T' * V' * C ; % method 0: Left, Transpose + elseif (method == 1) + C = C - V * T * V' * C ; % method 1: Left, No Transpose + elseif (method == 2) + C = C - C * V * T' * V' ; % method 2: Right, Transpose + elseif (method == 3) + C = C - C * V * T * V' ; % method 3: Right, No Transpose + end +*/ + +#include "spqr_subset.hpp" + +inline void spqr_private_larft (char direct, char storev, Int n, Int k, + double *V, Int ldv, double *Tau, double *T, Int ldt, cholmod_common *cc) +{ + BLAS_INT N = n, K = k, LDV = ldv, LDT = ldt ; + if (CHECK_BLAS_INT && + !(EQ (N,n) && EQ (K,k) && EQ (LDV,ldv) && EQ (LDT,ldt))) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_DLARFT (&direct, &storev, &N, &K, V, &LDV, Tau, T, &LDT) ; + } +} + +inline void spqr_private_larft (char direct, char storev, Int n, Int k, + Complex *V, Int ldv, Complex *Tau, Complex *T, Int ldt, cholmod_common *cc) +{ + BLAS_INT N = n, K = k, LDV = ldv, LDT = ldt ; + if (CHECK_BLAS_INT && + !(EQ (N,n) && EQ (K,k) && EQ (LDV,ldv) && EQ (LDT,ldt))) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_ZLARFT (&direct, &storev, &N, &K, V, &LDV, Tau, T, &LDT) ; + } +} + + +inline void spqr_private_larfb (char side, char trans, char direct, char storev, + Int m, Int n, Int k, double *V, Int ldv, double *T, Int ldt, double *C, + Int ldc, double *Work, Int ldwork, cholmod_common *cc) +{ + BLAS_INT M = m, N = n, K = k, LDV = ldv, LDT = ldt, LDC = ldc, + LDWORK = ldwork ; + if (CHECK_BLAS_INT && + !(EQ (M,m) && EQ (N,n) && EQ (K,k) && EQ (LDV,ldv) && + EQ (LDT,ldt) && EQ (LDV,ldv) && EQ (LDWORK,ldwork))) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_DLARFB (&side, &trans, &direct, &storev, &M, &N, &K, V, &LDV, + T, &LDT, C, &LDC, Work, &LDWORK) ; + } +} + + +inline void spqr_private_larfb (char side, char trans, char direct, char storev, + Int m, Int n, Int k, Complex *V, Int ldv, Complex *T, Int ldt, Complex *C, + Int ldc, Complex *Work, Int ldwork, cholmod_common *cc) +{ + char tr = (trans == 'T') ? 'C' : 'N' ; // change T to C + BLAS_INT M = m, N = n, K = k, LDV = ldv, LDT = ldt, LDC = ldc, + LDWORK = ldwork ; + if (CHECK_BLAS_INT && + !(EQ (M,m) && EQ (N,n) && EQ (K,k) && EQ (LDV,ldv) && + EQ (LDT,ldt) && EQ (LDV,ldv) && EQ (LDWORK,ldwork))) + { + cc->blas_ok = FALSE ; + } + if (!CHECK_BLAS_INT || cc->blas_ok) + { + LAPACK_ZLARFB (&side, &tr, &direct, &storev, &M, &N, &K, V, &LDV, + T, &LDT, C, &LDC, Work, &LDWORK) ; + } +} + + +// ============================================================================= + +template void spqr_larftb +( + // inputs, not modified (V is modified and then restored on output) + int method, // 0,1,2,3 + Int m, // C is m-by-n + Int n, + Int k, // V is v-by-k + // for methods 0 and 1, v = m, + // for methods 2 and 3, v = n + Int ldc, // leading dimension of C + Int ldv, // leading dimension of V + Entry *V, // V is v-by-k, unit lower triangular (diag not stored) + Entry *Tau, // size k, the k Householder coefficients + + // input/output + Entry *C, // C is m-by-n, with leading dimension ldc + + // workspace, not defined on input or output + Entry *W, // for methods 0,1: size k*k + n*k + // for methods 2,3: size k*k + m*k + cholmod_common *cc +) +{ + Entry *T, *Work ; + + // ------------------------------------------------------------------------- + // check inputs and split up workspace + // ------------------------------------------------------------------------- + + if (m <= 0 || n <= 0 || k <= 0) + { + return ; // nothing to do + } + + T = W ; // triangular k-by-k matrix for block reflector + Work = W + k*k ; // workspace of size n*k or m*k for larfb + + // ------------------------------------------------------------------------- + // construct and apply the k-by-k upper triangular matrix T + // ------------------------------------------------------------------------- + + // larft and larfb are always used "Forward" and "Columnwise" + + if (method == SPQR_QTX) + { + ASSERT (m >= k) ; + spqr_private_larft ('F', 'C', m, k, V, ldv, Tau, T, k, cc) ; + // Left, Transpose, Forward, Columwise: + spqr_private_larfb ('L', 'T', 'F', 'C', m, n, k, V, ldv, T, k, C, ldc, + Work, n, cc) ; + } + else if (method == SPQR_QX) + { + ASSERT (m >= k) ; + spqr_private_larft ('F', 'C', m, k, V, ldv, Tau, T, k, cc) ; + // Left, No Transpose, Forward, Columwise: + spqr_private_larfb ('L', 'N', 'F', 'C', m, n, k, V, ldv, T, k, C, ldc, + Work, n, cc) ; + } + else if (method == SPQR_XQT) + { + ASSERT (n >= k) ; + spqr_private_larft ('F', 'C', n, k, V, ldv, Tau, T, k, cc) ; + // Right, Transpose, Forward, Columwise: + spqr_private_larfb ('R', 'T', 'F', 'C', m, n, k, V, ldv, T, k, C, ldc, + Work, m, cc) ; + } + else if (method == SPQR_XQ) + { + ASSERT (n >= k) ; + spqr_private_larft ('F', 'C', n, k, V, ldv, Tau, T, k, cc) ; + // Right, No Transpose, Forward, Columwise: + spqr_private_larfb ('R', 'N', 'F', 'C', m, n, k, V, ldv, T, k, C, ldc, + Work, m, cc) ; + } +} + +// ============================================================================= + +template void spqr_larftb +( + // inputs, not modified (V is modified and then restored on output) + int method, // 0,1,2,3 + Int m, // C is m-by-n + Int n, + Int k, // V is v-by-k + // for methods 0 and 1, v = m, + // for methods 2 and 3, v = n + Int ldc, // leading dimension of C + Int ldv, // leading dimension of V + double *V, // V is v-by-k, unit lower triangular (diag not stored) + double *Tau, // size k, the k Householder coefficients + + // input/output + double *C, // C is m-by-n, with leading dimension ldc + + // workspace, not defined on input or output + double *W, // for methods 0,1: size k*k + n*k + // for methods 2,3: size k*k + m*k + cholmod_common *cc +) ; + +// ============================================================================= + +template void spqr_larftb +( + // inputs, not modified (V is modified and then restored on output) + int method, // 0,1,2,3 + Int m, // C is m-by-n + Int n, + Int k, // V is v-by-k + // for methods 0 and 1, v = m, + // for methods 2 and 3, v = n + Int ldc, // leading dimension of C + Int ldv, // leading dimension of V + Complex *V, // V is v-by-k, unit lower triangular (diag not stored) + Complex *Tau, // size k, the k Householder coefficients + + // input/output + Complex *C, // C is m-by-n, with leading dimension ldc + + // workspace, not defined on input or output + Complex *W, // for methods 0,1: size k*k + n*k + // for methods 2,3: size k*k + m*k + cholmod_common *cc +) ; diff --git a/spqr_mini/spqr_larftb.h b/spqr_mini/spqr_larftb.h new file mode 100644 index 000000000..e69de29bb diff --git a/spqr_mini/spqr_subset.hpp b/spqr_mini/spqr_subset.hpp new file mode 100644 index 000000000..aad6c798a --- /dev/null +++ b/spqr_mini/spqr_subset.hpp @@ -0,0 +1,397 @@ +// ============================================================================= +// === spqr.hpp ================================================================ +// ============================================================================= + +// Internal definitions and non-user-callable routines. This should not be +// included in the user's code. + +#ifndef SPQR_INTERNAL_H +#define SPQR_INTERNAL_H + +// ----------------------------------------------------------------------------- +// include files +// ----------------------------------------------------------------------------- + +#include "UFconfig.h" +extern "C" { +#include "cholmod_core.h" +#include "cholmod_blas.h" +} +#include "SuiteSparseQR_definitions.h" +#include +#include +#include +#include +#include + +#include +typedef std::complex Complex ; + +// ----------------------------------------------------------------------------- +// debugging and printing control +// ----------------------------------------------------------------------------- + +// force debugging off +#ifndef NDEBUG +#define NDEBUG +#endif + +// force printing off +#ifndef NPRINT +#define NPRINT +#endif + +// uncomment the following line to turn on debugging (SPQR will be slow!) +/* +#undef NDEBUG +*/ + +// uncomment the following line to turn on printing (LOTS of output!) +/* +#undef NPRINT +*/ + +// uncomment the following line to turn on expensive debugging (very slow!) +/* +#define DEBUG_EXPENSIVE +*/ + +// ----------------------------------------------------------------------------- +// Int is defined at UF_long, from UFconfig.h +// ----------------------------------------------------------------------------- + +#define Int UF_long +#define Int_max UF_long_max + +// ----------------------------------------------------------------------------- +// basic macros +// ----------------------------------------------------------------------------- + +#define MIN(a,b) (((a) < (b)) ? (a) : (b)) +#define MAX(a,b) (((a) > (b)) ? (a) : (b)) +#define EMPTY (-1) +#define TRUE 1 +#define FALSE 0 +#define IMPLIES(p,q) (!(p) || (q)) + +// NULL should already be defined, but ensure it is here. +#ifndef NULL +#define NULL ((void *) 0) +#endif + +// column-major indexing; A[i,j] is A (INDEX (i,j,lda)) +#define INDEX(i,j,lda) ((i) + ((j)*(lda))) + +// FLIP is a "negation about -1", and is used to mark an integer i that is +// normally non-negative. FLIP (EMPTY) is EMPTY. FLIP of a number > EMPTY +// is negative, and FLIP of a number < EMTPY is positive. FLIP (FLIP (i)) = i +// for all integers i. UNFLIP (i) is >= EMPTY. +#define EMPTY (-1) +#define FLIP(i) (-(i)-2) +#define UNFLIP(i) (((i) < EMPTY) ? FLIP (i) : (i)) + +// ----------------------------------------------------------------------------- +// additional include files +// ----------------------------------------------------------------------------- + +#ifdef MATLAB_MEX_FILE +#include "mex.h" +#endif + +#define ITYPE CHOLMOD_LONG +#define DTYPE CHOLMOD_DOUBLE +#define ID UF_long_id + +// ----------------------------------------------------------------------------- + +#define ERROR(status,msg) \ + printf ("CHOLMOD error: %s\n",msg) // Kai: disable cholmod_l_error to prevent from including tons of files + +// Check a pointer and return if null. Set status to invalid, unless the +// status is already "out of memory" +#define RETURN_IF_NULL(A,result) \ +{ \ + if ((A) == NULL) \ + { \ + if (cc->status != CHOLMOD_OUT_OF_MEMORY) \ + { \ + ERROR (CHOLMOD_INVALID, NULL) ; \ + } \ + return (result) ; \ + } \ +} + +// Return if Common is NULL or invalid +#define RETURN_IF_NULL_COMMON(result) \ +{ \ + if (cc == NULL) \ + { \ + return (result) ; \ + } \ + if (cc->itype != ITYPE || cc->dtype != DTYPE) \ + { \ + cc->status = CHOLMOD_INVALID ; \ + return (result) ; \ + } \ +} + +#define RETURN_IF_XTYPE_INVALID(A,result) \ +{ \ + if (A->xtype != xtype) \ + { \ + ERROR (CHOLMOD_INVALID, "invalid xtype") ; \ + return (result) ; \ + } \ +} + +// ----------------------------------------------------------------------------- +// debugging and printing macros +// ----------------------------------------------------------------------------- + +#ifndef NDEBUG + + #ifdef MATLAB_MEX_FILE + + // #define ASSERT(e) mxAssert (e, "error: ") + + extern char spqr_mx_debug_string [200] ; + char *spqr_mx_id (int line) ; + + #define ASSERT(e) \ + ((e) ? (void) 0 : \ + mexErrMsgIdAndTxt (spqr_mx_id (__LINE__), \ + "assert: (" #e ") file:" __FILE__ )) + + #else + + #include + #define ASSERT(e) assert (e) + + #endif + + #define DEBUG(e) e + #ifdef DEBUG_EXPENSIVE + #define DEBUG2(e) e + #define ASSERT2(e) ASSERT(e) + #else + #define DEBUG2(e) + #define ASSERT2(e) + #endif + +#else + + #define ASSERT(e) + #define ASSERT2(e) + #define DEBUG(e) + #define DEBUG2(e) + +#endif + +#ifndef NPRINT + + #ifdef MATLAB_MEX_FILE + #define PR(e) mexPrintf e + #else + #define PR(e) printf e + #endif + + #define PRVAL(e) spqrDebug_print (e) + +#else + + #define PR(e) + #define PRVAL(e) + +#endif + +// ----------------------------------------------------------------------------- +// For counting flops; disabled if TBB is used or timing not enabled +// ----------------------------------------------------------------------------- + +#if defined(TIMING) +#define FLOP_COUNT(f) { if (cc->SPQR_grain <= 1) cc->other1 [0] += (f) ; } +#else +#define FLOP_COUNT(f) +#endif + +template void spqr_larftb +( + // inputs, not modified (V is modified and then restored on output) + int method, // 0,1,2,3 + Int m, // C is m-by-n + Int n, + Int k, // V is v-by-k + // for methods 0 and 1, v = m, + // for methods 2 and 3, v = n + Int ldc, // leading dimension of C + Int ldv, // leading dimension of V + Entry *V, // V is v-by-k, unit lower triangular (diag not stored) + Entry *Tau, // size k, the k Householder coefficients + + // input/output + Entry *C, // C is m-by-n, with leading dimension ldc + + // workspace, not defined on input or output + Entry *W, // for methods 0,1: size k*k + n*k + // for methods 2,3: size k*k + m*k + cholmod_common *cc +) ; + +// returns rank of F, or 0 on error +template Int spqr_front +( + // input, not modified + Int m, // F is m-by-n with leading dimension m + Int n, + Int npiv, // number of pivot columns + double tol, // a column is flagged as dead if its norm is <= tol + Int ntol, // apply tol only to first ntol pivot columns + Int fchunk, // block size for compact WY Householder reflections, + // treated as 1 if fchunk <= 1 + + // input/output + Entry *F, // frontal matrix F of size m-by-n + Int *Stair, // size n, entries F (Stair[k]:m-1, k) are all zero, + // and remain zero on output. + char *Rdead, // size npiv; all zero on input. If k is dead, + // Rdead [k] is set to 1 + + // output, not defined on input + Entry *Tau, // size n, Householder coefficients + + // workspace, undefined on input and output + Entry *W, // size b*(n+b), where b = min (fchunk,n,m) + + // input/output + double *wscale, + double *wssq, + + cholmod_common *cc // for cc->hypotenuse function +) ; + + +// ============================================================================= +// === spqr_conj =============================================================== +// ============================================================================= + +inline double spqr_conj (double x) +{ + return (x) ; +} + +inline Complex spqr_conj (Complex x) +{ + return (std::conj (x)) ; +} + +// ============================================================================= +// === spqr_abs ================================================================ +// ============================================================================= + +inline double spqr_abs (double x, cholmod_common *cc) // cc is unused +{ + return (fabs (x)) ; +} + +inline double spqr_abs (Complex x, cholmod_common *cc) +{ + return (cc->hypotenuse (x.real ( ), x.imag ( ))) ; +} + +// ============================================================================= +// === BLAS interface ========================================================== +// ============================================================================= + +// To compile SuiteSparseQR with 64-bit BLAS, use -DBLAS64. See also +// CHOLMOD/Include/cholmod_blas.h + +extern "C" { +#include "cholmod_blas.h" +} + +#ifdef SUN64 + +#define BLAS_DNRM2 dnrm2_64_ +#define LAPACK_DLARF dlarf_64_ +#define LAPACK_DLARFG dlarfg_64_ +#define LAPACK_DLARFT dlarft_64_ +#define LAPACK_DLARFB dlarfb_64_ + +#define BLAS_DZNRM2 dznrm2_64_ +#define LAPACK_ZLARF zlarf_64_ +#define LAPACK_ZLARFG zlarfg_64_ +#define LAPACK_ZLARFT zlarft_64_ +#define LAPACK_ZLARFB zlarfb_64_ + +#elif defined (BLAS_NO_UNDERSCORE) + +#define BLAS_DNRM2 dnrm2 +#define LAPACK_DLARF dlarf +#define LAPACK_DLARFG dlarfg +#define LAPACK_DLARFT dlarft +#define LAPACK_DLARFB dlarfb + +#define BLAS_DZNRM2 dznrm2 +#define LAPACK_ZLARF zlarf +#define LAPACK_ZLARFG zlarfg +#define LAPACK_ZLARFT zlarft +#define LAPACK_ZLARFB zlarfb + +#else + +#define BLAS_DNRM2 dnrm2_ +#define LAPACK_DLARF dlarf_ +#define LAPACK_DLARFG dlarfg_ +#define LAPACK_DLARFT dlarft_ +#define LAPACK_DLARFB dlarfb_ + +#define BLAS_DZNRM2 dznrm2_ +#define LAPACK_ZLARF zlarf_ +#define LAPACK_ZLARFG zlarfg_ +#define LAPACK_ZLARFT zlarft_ +#define LAPACK_ZLARFB zlarfb_ + +#endif + +// ============================================================================= +// === BLAS and LAPACK prototypes ============================================== +// ============================================================================= + +extern "C" +{ + +void LAPACK_DLARFT (char *direct, char *storev, BLAS_INT *n, BLAS_INT *k, + double *V, BLAS_INT *ldv, double *Tau, double *T, BLAS_INT *ldt) ; + +void LAPACK_ZLARFT (char *direct, char *storev, BLAS_INT *n, BLAS_INT *k, + Complex *V, BLAS_INT *ldv, Complex *Tau, Complex *T, BLAS_INT *ldt) ; + +void LAPACK_DLARFB (char *side, char *trans, char *direct, char *storev, + BLAS_INT *m, BLAS_INT *n, BLAS_INT *k, double *V, BLAS_INT *ldv, + double *T, BLAS_INT *ldt, double *C, BLAS_INT *ldc, double *Work, + BLAS_INT *ldwork) ; + +void LAPACK_ZLARFB (char *side, char *trans, char *direct, char *storev, + BLAS_INT *m, BLAS_INT *n, BLAS_INT *k, Complex *V, BLAS_INT *ldv, + Complex *T, BLAS_INT *ldt, Complex *C, BLAS_INT *ldc, Complex *Work, + BLAS_INT *ldwork) ; + +double BLAS_DNRM2 (BLAS_INT *n, double *X, BLAS_INT *incx) ; + +double BLAS_DZNRM2 (BLAS_INT *n, Complex *X, BLAS_INT *incx) ; + +void LAPACK_DLARFG (BLAS_INT *n, double *alpha, double *X, BLAS_INT *incx, + double *tau) ; + +void LAPACK_ZLARFG (BLAS_INT *n, Complex *alpha, Complex *X, BLAS_INT *incx, + Complex *tau) ; + +void LAPACK_DLARF (char *side, BLAS_INT *m, BLAS_INT *n, double *V, + BLAS_INT *incv, double *tau, double *C, BLAS_INT *ldc, double *Work) ; + +void LAPACK_ZLARF (char *side, BLAS_INT *m, BLAS_INT *n, Complex *V, + BLAS_INT *incv, Complex *tau, Complex *C, BLAS_INT *ldc, Complex *Work) ; + +} + +#endif