00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <suitesparse/cholmod.h>
00039 #include <suitesparse/umfpack.h>
00040 #include <iostream>
00041 #include <stdio.h>
00042 #include <stdexcept>
00043
00044 #include <pcl/surface/on_nurbs/nurbs_solve.h>
00045
00046 using namespace std;
00047 using namespace pcl;
00048 using namespace on_nurbs;
00049
00050 void
00051 NurbsSolve::assign (unsigned rows, unsigned cols, unsigned dims)
00052 {
00053 m_Ksparse.clear ();
00054 m_xeig = Eigen::MatrixXd::Zero (cols, dims);
00055 m_feig = Eigen::MatrixXd::Zero (rows, dims);
00056 }
00057
00058 void
00059 NurbsSolve::K (unsigned i, unsigned j, double v)
00060 {
00061 m_Ksparse.set (i, j, v);
00062 }
00063 void
00064 NurbsSolve::x (unsigned i, unsigned j, double v)
00065 {
00066 m_xeig (i, j) = v;
00067 }
00068 void
00069 NurbsSolve::f (unsigned i, unsigned j, double v)
00070 {
00071 m_feig (i, j) = v;
00072 }
00073
00074 double
00075 NurbsSolve::K (unsigned i, unsigned j)
00076 {
00077 return m_Ksparse.get (i, j);
00078 }
00079 double
00080 NurbsSolve::x (unsigned i, unsigned j)
00081 {
00082 return m_xeig (i, j);
00083 }
00084 double
00085 NurbsSolve::f (unsigned i, unsigned j)
00086 {
00087 return m_feig (i, j);
00088 }
00089
00090 void
00091 NurbsSolve::resize (unsigned rows)
00092 {
00093 m_feig.conservativeResize (rows, m_feig.cols ());
00094 }
00095
00096 void
00097 NurbsSolve::printK ()
00098 {
00099 m_Ksparse.printLong ();
00100 }
00101
00102 void
00103 NurbsSolve::printX ()
00104 {
00105 for (unsigned r = 0; r < m_xeig.rows (); r++)
00106 {
00107 for (unsigned c = 0; c < m_xeig.cols (); c++)
00108 {
00109 printf (" %f", m_xeig (r, c));
00110 }
00111 printf ("\n");
00112 }
00113 }
00114
00115 void
00116 NurbsSolve::printF ()
00117 {
00118 for (unsigned r = 0; r < m_feig.rows (); r++)
00119 {
00120 for (unsigned c = 0; c < m_feig.cols (); c++)
00121 {
00122 printf (" %f", m_feig (r, c));
00123 }
00124 printf ("\n");
00125 }
00126 }
00127
00128 namespace pcl
00129 {
00130 namespace on_nurbs
00131 {
00132 bool
00133 solveSparseLinearSystem (cholmod_sparse* A, cholmod_dense* b, cholmod_dense* x, bool transpose)
00134 {
00135 double* vals = (double*)A->x;
00136 int* cols = (int*)A->p;
00137 int* rows = (int*)A->i;
00138 double* rhs = (double*)b->x;
00139 double* sol = (double*)x->x;
00140
00141 int noOfVerts = b->nrow;
00142 int noOfCols = b->ncol;
00143
00144 double* tempRhs = new double[noOfVerts];
00145 double* tempSol = new double[noOfVerts];
00146
00147 int i, k, status;
00148 double* null = (double*)NULL;
00149 void *Symbolic, *Numeric;
00150
00151 status = umfpack_di_symbolic (A->nrow, A->ncol, cols, rows, vals, &Symbolic, null, null);
00152
00153 if (status != 0)
00154 {
00155 std::cout << "[NurbsSolve[UMFPACK]::solveSparseLinearSystem] Warning: something is wrong with input matrix!"
00156 << std::endl;
00157 delete [] tempRhs;
00158 delete [] tempSol;
00159 return false;
00160
00161 }
00162
00163 status = umfpack_di_numeric (cols, rows, vals, Symbolic, &Numeric, null, null);
00164
00165 if (status != 0)
00166 {
00167 std::cout
00168 << "[NurbsSolve[UMFPACK]::solveSparseLinearSystem] Warning: ordering was ok but factorization failed!"
00169 << std::endl;
00170 delete [] tempRhs;
00171 delete [] tempSol;
00172 return false;
00173 }
00174
00175 umfpack_di_free_symbolic (&Symbolic);
00176
00177 for (i = 0; i < noOfCols; i++)
00178 {
00179 for (k = 0; k < noOfVerts; k++)
00180 tempRhs[k] = rhs[i * noOfVerts + k];
00181
00182
00183 if (transpose)
00184 umfpack_di_solve (UMFPACK_At, cols, rows, vals, tempSol, tempRhs, Numeric, null, null);
00185 else
00186 umfpack_di_solve (UMFPACK_A, cols, rows, vals, tempSol, tempRhs, Numeric, null, null);
00187
00188 for (k = 0; k < noOfVerts; k++)
00189 sol[i * noOfVerts + k] = tempSol[k];
00190 }
00191
00192
00193 umfpack_di_free_numeric (&Numeric);
00194 delete [] tempRhs;
00195 delete [] tempSol;
00196 return true;
00197 }
00198
00199 bool
00200 solveSparseLinearSystemLQ (cholmod_sparse* A, cholmod_dense* b, cholmod_dense* x)
00201 {
00202 cholmod_common c;
00203 cholmod_start (&c);
00204 c.print = 4;
00205
00206 cholmod_sparse* At = cholmod_allocate_sparse (A->ncol, A->nrow, A->ncol * A->nrow, 0, 1, 0, CHOLMOD_REAL, &c);
00207
00208 cholmod_dense* Atb = cholmod_allocate_dense (A->ncol, b->ncol, A->ncol, CHOLMOD_REAL, &c);
00209
00210 double one[2] = {1, 0};
00211 double zero[2] = {0, 0};
00212 cholmod_sdmult (A, 1, one, zero, b, Atb, &c);
00213
00214 unsigned trials (20);
00215 unsigned i (0);
00216 while (!cholmod_transpose_unsym (A, 1, NULL, NULL, A->ncol, At, &c) && i < trials)
00217 {
00218 printf (
00219 "[NurbsSolveUmfpack::solveSparseLinearSystemLQ] Warning allocated memory to low, trying to increase %dx\n",
00220 (i + 2));
00221
00222 cholmod_free_sparse (&At, &c);
00223 cholmod_free_dense (&Atb, &c);
00224
00225 At = cholmod_allocate_sparse (A->ncol, A->nrow, (i + 2) * A->ncol * A->nrow, 0, 1, 0, CHOLMOD_REAL, &c);
00226 Atb = cholmod_allocate_dense (A->ncol, b->ncol, A->ncol, CHOLMOD_REAL, &c);
00227
00228 double one[2] = {1, 0};
00229 double zero[2] = {0, 0};
00230 cholmod_sdmult (A, 1, one, zero, b, Atb, &c);
00231 i++;
00232 }
00233
00234 if (i == trials)
00235 {
00236 printf ("[NurbsSolveUmfpack::solveSparseLinearSystemLQ] Not enough memory for system to solve. (%d trials)\n",
00237 trials);
00238 cholmod_free_sparse (&At, &c);
00239 cholmod_free_dense (&Atb, &c);
00240 return false;
00241 }
00242
00243 cholmod_sparse* AtA = cholmod_ssmult (At, A, 0, 1, 1, &c);
00244
00245
00246
00247 bool success = solveSparseLinearSystem (AtA, Atb, x, false);
00248
00249 cholmod_free_sparse (&At, &c);
00250 cholmod_free_sparse (&AtA, &c);
00251 cholmod_free_dense (&Atb, &c);
00252
00253 cholmod_finish (&c);
00254
00255 return success;
00256 }
00257 }
00258 }
00259
00260 bool
00261 NurbsSolve::solve ()
00262 {
00263 clock_t time_start, time_end;
00264 time_start = clock ();
00265
00266 cholmod_common c;
00267 cholmod_start (&c);
00268
00269 int n_rows, n_cols, n_dims, n_nz;
00270 m_Ksparse.size (n_rows, n_cols);
00271 n_nz = m_Ksparse.nonzeros ();
00272 n_dims = m_feig.cols ();
00273
00274
00275
00276 cholmod_sparse* K = cholmod_allocate_sparse (n_rows, n_cols, n_rows * n_cols, 0, 1, 0, CHOLMOD_REAL, &c);
00277 cholmod_dense* f = cholmod_allocate_dense (n_rows, n_dims, n_rows, CHOLMOD_REAL, &c);
00278 cholmod_dense* d = cholmod_allocate_dense (n_cols, n_dims, n_cols, CHOLMOD_REAL, &c);
00279
00280 std::vector<int> rowinds;
00281 std::vector<int> colinds;
00282 std::vector<double> values;
00283 m_Ksparse.get (rowinds, colinds, values);
00284
00285 double* vals = (double*)K->x;
00286 int* cols = (int*)K->p;
00287 int* rows = (int*)K->i;
00288
00289 umfpack_di_triplet_to_col (n_rows, n_cols, n_nz, &rowinds[0], &colinds[0], &values[0], cols, rows, vals, NULL);
00290
00291 double* temp = (double*)f->x;
00292
00293 for (int j = 0; j < n_dims; j++)
00294 {
00295 for (int i = 0; i < n_rows; i++)
00296 {
00297
00298 temp[j * n_rows + i] = m_feig (i, j);
00299
00300 }
00301 }
00302
00303 bool success = solveSparseLinearSystemLQ (K, f, d);
00304
00305 temp = (double*)d->x;
00306
00307 for (int j = 0; j < n_dims; j++)
00308 {
00309 for (int i = 0; i < n_cols; i++)
00310 {
00311
00312 m_xeig (i, j) = temp[j * n_cols + i];
00313
00314 }
00315 }
00316
00317 cholmod_free_sparse (&K, &c);
00318 cholmod_free_dense (&f, &c);
00319 cholmod_free_dense (&d, &c);
00320
00321 cholmod_finish (&c);
00322
00323 time_end = clock ();
00324
00325 if (success)
00326 {
00327 if (!m_quiet)
00328 {
00329 double solve_time = (double)(time_end - time_start) / (double)(CLOCKS_PER_SEC);
00330 printf ("[NurbsSolve[UMFPACK]::solve()] solution found! (%f sec)\n", solve_time);
00331 }
00332 }
00333 else
00334 {
00335 printf ("[NurbsSolve[UMFPACK]::solve()] Error: solution NOT found\n");
00336 }
00337
00338 return success;
00339 }
00340
00341 Eigen::MatrixXd
00342 NurbsSolve::diff ()
00343 {
00344
00345 int n_rows, n_cols, n_dims;
00346 m_Ksparse.size (n_rows, n_cols);
00347 n_dims = m_feig.cols ();
00348
00349 if (n_rows != m_feig.rows ())
00350 {
00351 printf ("[NurbsSolve::diff] K.rows: %d f.rows: %d\n", n_rows, (int)m_feig.rows ());
00352 throw std::runtime_error ("[NurbsSolve::diff] Rows of equation do not match\n");
00353 }
00354
00355 Eigen::MatrixXd f = Eigen::MatrixXd::Zero (n_rows, n_dims);
00356
00357 for (int r = 0; r < n_rows; r++)
00358 {
00359 for (int c = 0; c < n_cols; c++)
00360 {
00361 f.row (r) = f.row (r) + m_xeig.row (c) * m_Ksparse.get (r, c);
00362 }
00363 }
00364
00365 return (f - m_feig);
00366 }
00367