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
00039
00040 #ifndef _BPCG_H_
00041 #define _BPCG_H_
00042
00043 #ifndef EIGEN_USE_NEW_STDVECTOR
00044 #define EIGEN_USE_NEW_STDVECTOR
00045 #endif // EIGEN_USE_NEW_STDVECTOR
00046
00047 #include <vector>
00048 #include <map>
00049 #include <Eigen/Core>
00050 #include <Eigen/Geometry>
00051 #include <Eigen/LU>
00052 #include <Eigen/StdVector>
00053
00054 using namespace Eigen;
00055 using namespace std;
00056
00057
00058
00059 #define AVNd typename Matrix<double,N,1>::AlignedMapType
00060
00061 namespace sba
00062 {
00064
00065 template <int N>
00066 class jacobiBPCG
00067 {
00068 public:
00069 jacobiBPCG() { residual = 0.0; };
00070 int doBPCG(int iters, double tol,
00071 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00072 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00073 VectorXd &x,
00074 VectorXd &b,
00075 bool abstol = false,
00076 bool verbose = false
00077 );
00078
00079
00080 int doBPCG2(int iters, double tol,
00081 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00082 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00083 VectorXd &x,
00084 VectorXd &b,
00085 bool abstol = false,
00086 bool verbose = false
00087 );
00088
00089 double residual;
00090
00091 private:
00092 void mMV(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00093 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00094 const VectorXd &vin,
00095 VectorXd &vout);
00096
00097
00098 void mMV2(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00099 const VectorXd &vin,
00100 VectorXd &vout);
00101
00102 void mD(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00103 VectorXd &vin,
00104 VectorXd &vout);
00105
00106 vector<int> vcind, vrind;
00107 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > vcols;
00108 };
00109
00110 template <int N>
00111 void jacobiBPCG<N>::mMV(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00112 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00113 const VectorXd &vin,
00114 VectorXd &vout)
00115 {
00116
00117 if (cols.size() > 0)
00118 for (int i=0; i<(int)cols.size(); i++)
00119 {
00120 AVNd(&vout(i*N)) = diag[i]*AVNd(&vin(i*N));
00121
00122 map<int,Matrix<double,N,N>, less<int>,
00123 aligned_allocator<Matrix<double,N,N> > > &col = cols[i];
00124 if (col.size() > 0)
00125 {
00126 typename map<int,Matrix<double,N,N>, less<int>,
00127 aligned_allocator<Matrix<double,N,N > > >::iterator it;
00128 for (it = col.begin(); it != col.end(); it++)
00129 {
00130 int ri = (*it).first;
00131 const Matrix<double,N,N> &M = (*it).second;
00132 AVNd(&vout(i*N)) += M.transpose()*AVNd(&vin(ri*N));
00133 AVNd(&vout(ri*N)) += M*AVNd(&vin(i*N));
00134 }
00135 }
00136 }
00137 }
00138
00139
00140
00141
00142
00143 template <int N>
00144 void jacobiBPCG<N>::mMV2(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00145 const VectorXd &vin,
00146 VectorXd &vout)
00147 {
00148
00149
00150 if (diag.size() > 0)
00151 for (int i=0; i<(int)diag.size(); i++)
00152 AVNd(&vout(i*N)) = diag[i]*AVNd(&vin(i*N));
00153
00154 for (int i=0; i<(int)vcind.size(); i++)
00155 {
00156 int ri = vrind[i];
00157 int ii = vcind[i];
00158 const Matrix<double,N,N> &M = vcols[i];
00159 AVNd(&vout(ri*N)) += M*AVNd(&vin(ii*N));
00160 AVNd(&vout(ii*N)) += M.transpose()*AVNd(&vin(ri*N));
00161 }
00162 }
00163
00164
00165
00166
00167 template <int N>
00168 void jacobiBPCG<N>::mD(vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00169 VectorXd &vin,
00170 VectorXd &vout)
00171 {
00172
00173 for (int i=0; i<(int)diag.size(); i++)
00174 AVNd(&vout(i*N)) = diag[i]*AVNd(&vin(i*N));
00175 }
00176
00177
00178 template <int N>
00179 int jacobiBPCG<N>::doBPCG(int iters, double tol,
00180 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00181 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00182 VectorXd &x,
00183 VectorXd &b,
00184 bool abstol,
00185 bool verbose)
00186 {
00187
00188 VectorXd r,d,q,s;
00189 int n = diag.size();
00190 int n6 = n*N;
00191 r.setZero(n6);
00192 d.setZero(n6);
00193 q.setZero(n6);
00194 s.setZero(n6);
00195
00196
00197 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > J;
00198 J.resize(n);
00199 for (int i=0; i<n; i++)
00200 J[i] = diag[i].inverse();
00201
00202 int i;
00203 r = b;
00204 mD(J,r,d);
00205 double dn = r.dot(d);
00206 double d0 = tol*dn;
00207 if (abstol)
00208 {
00209 if (residual > d0) d0 = residual;
00210 }
00211
00212 for (i=0; i<iters; i++)
00213 {
00214 if (verbose && 0)
00215 cout << "[BPCG] residual[" << i << "]: " << dn << " < " << d0 << endl;
00216 if (dn < d0) break;
00217 mMV(diag,cols,d,q);
00218 double a = dn / d.dot(q);
00219 x += a*d;
00220
00221 r -= a*q;
00222 mD(J,r,s);
00223 double dold = dn;
00224 dn = r.dot(s);
00225 double ba = dn / dold;
00226 d = s + ba*d;
00227 }
00228
00229
00230 if (verbose)
00231 cout << "[BPCG] residual[" << i << "]: " << dn << endl;
00232 residual = dn/2.0;
00233 return i;
00234 }
00235
00236
00237
00238 template <int N>
00239 int jacobiBPCG<N>::doBPCG2(int iters, double tol,
00240 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > &diag,
00241 vector< map<int,Matrix<double,N,N>, less<int>, aligned_allocator<Matrix<double,N,N> > > > &cols,
00242 VectorXd &x,
00243 VectorXd &b,
00244 bool abstol,
00245 bool verbose)
00246 {
00247
00248 VectorXd r,d,q,s;
00249 int n = diag.size();
00250 int n6 = n*N;
00251 r.setZero(n6);
00252 d.setZero(n6);
00253 q.setZero(n6);
00254 s.setZero(n6);
00255
00256 vcind.clear();
00257 vrind.clear();
00258 vcols.clear();
00259
00260
00261 for (int i=0; i<(int)cols.size(); i++)
00262 {
00263 map<int,Matrix<double,N,N>, less<int>,
00264 aligned_allocator<Matrix<double,N,N> > > &col = cols[i];
00265 if (col.size() > 0)
00266 {
00267 typename map<int,Matrix<double,N,N>, less<int>,
00268 aligned_allocator<Matrix<double,N,N> > >::iterator it;
00269 for (it = col.begin(); it != col.end(); it++)
00270 {
00271 int ri = (*it).first;
00272 vrind.push_back(ri);
00273 vcind.push_back(i);
00274 vcols.push_back((*it).second);
00275 }
00276 }
00277 }
00278
00279
00280 vector< Matrix<double,N,N>, aligned_allocator<Matrix<double,N,N> > > J;
00281 J.resize(n);
00282 for (int i=0; i<n; i++)
00283 J[i] = diag[i].inverse();
00284
00285 int i;
00286 r = b;
00287 mD(J,r,d);
00288 double dn = r.dot(d);
00289 double d0 = tol*dn;
00290 if (abstol)
00291 {
00292 if (residual > d0) d0 = residual;
00293 }
00294
00295 for (i=0; i<iters; i++)
00296 {
00297 if (verbose && 0)
00298 cout << "[BPCG] residual[" << i << "]: " << dn << " < " << d0 << endl;
00299 if (dn < d0) break;
00300 mMV2(diag,d,q);
00301 double a = dn / d.dot(q);
00302 x += a*d;
00303
00304 r -= a*q;
00305 mD(J,r,s);
00306 double dold = dn;
00307 dn = r.dot(s);
00308 double ba = dn / dold;
00309 d = s + ba*d;
00310 }
00311
00312
00313 if (verbose)
00314 cout << "[BPCG] residual[" << i << "]: " << dn << endl;
00315 residual = dn/2.0;
00316 return i;
00317 }
00318
00319
00320 #if 0
00321
00322
00323
00324
00325 void
00326 mMV(vector< Matrix<double,6,6>, aligned_allocator<Matrix<double,6,6> > > &diag,
00327 vector< map<int,Matrix<double,6,6>, less<int>, aligned_allocator<Matrix<double,6,6> > > > &cols,
00328 const VectorXd &vin,
00329 VectorXd &vout);
00330
00331
00332
00333
00334
00335 int
00336 bpcg_jacobi(int iters, double tol,
00337 vector< Matrix<double,6,6>, aligned_allocator<Matrix<double,6,6> > > &diag,
00338 vector< map<int,Matrix<double,6,6>, less<int>, aligned_allocator<Matrix<double,6,6> > > > &cols,
00339 VectorXd &x,
00340 VectorXd &b,
00341 bool abstol = false,
00342 bool verbose = false
00343 );
00344
00345 int
00346 bpcg_jacobi_dense(int iters, double tol,
00347 MatrixXd &M,
00348 VectorXd &x,
00349 VectorXd &b);
00350
00351
00352
00353
00354
00355 int
00356 bpcg_jacobi3(int iters, double tol,
00357 vector< Matrix<double,3,3>, aligned_allocator<Matrix<double,3,3> > > &diag,
00358 vector< map<int,Matrix<double,3,3>, less<int>, aligned_allocator<Matrix<double,3,3> > > > &cols,
00359 VectorXd &x,
00360 VectorXd &b,
00361 bool abstol = false,
00362 bool verbose = false
00363 );
00364
00365 int
00366 bpcg_jacobi_dense3(int iters, double tol,
00367 MatrixXd &M,
00368 VectorXd &x,
00369 VectorXd &b);
00370
00371 #endif
00372
00373 }
00374
00375 #endif // BPCG_H