$search
00001 /*************************************************************************** 00002 pinv.cxx - description 00003 ------------------------- 00004 begin : June 2006 00005 copyright : (C) 2006 Erwin Aertbelien 00006 email : firstname.lastname@mech.kuleuven.ac.be 00007 00008 History (only major changes)( AUTHOR-Description ) : 00009 00010 *************************************************************************** 00011 * This library is free software; you can redistribute it and/or * 00012 * modify it under the terms of the GNU Lesser General Public * 00013 * License as published by the Free Software Foundation; either * 00014 * version 2.1 of the License, or (at your option) any later version. * 00015 * * 00016 * This library is distributed in the hope that it will be useful, * 00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of * 00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU * 00019 * Lesser General Public License for more details. * 00020 * * 00021 * You should have received a copy of the GNU Lesser General Public * 00022 * License along with this library; if not, write to the Free Software * 00023 * Foundation, Inc., 59 Temple Place, * 00024 * Suite 330, Boston, MA 02111-1307 USA * 00025 * * 00026 ***************************************************************************/ 00027 00028 00029 #include <math.h> 00030 #include <assert.h> 00031 #include <kdl/pinv.hpp> 00032 #include <iostream> 00033 #include <algorithm> 00034 00035 inline double PYTHAG(double a,double b) { 00036 double at,bt,ct; 00037 at = fabs(a); 00038 bt = fabs(b); 00039 if (at > bt ) { 00040 ct=bt/at; 00041 return at*sqrt(1.0+ct*ct); 00042 } else { 00043 if (bt==0) 00044 return 0.0; 00045 else { 00046 ct=at/bt; 00047 return bt*sqrt(1.0+ct*ct); 00048 } 00049 } 00050 } 00051 00052 00053 inline double SIGN(double a,double b) { 00054 return ((b) >= 0.0 ? fabs(a) : -fabs(a)); 00055 } 00056 00083 int svdcmp( 00084 double *a, 00085 int stridea, 00086 int m,int n, 00087 double* w, 00088 double* v, 00089 int stridev, 00090 int NrIts, 00091 double* vec ) 00092 { 00093 double maxarg1,maxarg2; 00094 int flag,i,its=0,j,jj,k,l=0,nm=0; 00095 double c,f,h,s,x,y,z; 00096 double anorm=0.0,g=0.0,scale=0.0; 00097 00098 /* adapt conventions from 0-based to 1-based */ 00099 a = a - stridea - 1; 00100 w = w - 1; 00101 v = v - stridev - 1; 00102 vec = vec - 1; 00103 /*****/ 00104 if (m<n) return(1); 00105 /* Householder reduction to bidiagonal form. */ 00106 for (i=1;i<=n;++i) { 00107 l=i+1; 00108 vec[i]=scale*g; 00109 g=s=scale=0.0; 00110 if (i<=m) { 00111 for (k=i;k<=m;++k) scale += fabs(a[k*stridea+i]); 00112 if (scale) { 00113 for (k=i;k<=m;++k) { 00114 a[k*stridea+i] /= scale; 00115 s += a[k*stridea+i]*a[k*stridea+i]; 00116 } 00117 f=a[i*stridea+i]; 00118 g = -SIGN(sqrt(s),f); 00119 h=f*g-s; 00120 a[i*stridea+i]=f-g; 00121 if (i != n) { 00122 for (j=l;j<=n;++j) { 00123 for (s=0.0,k=i;k<=m;++k) s += a[k*stridea+i]*a[k*stridea+j]; 00124 f=s/h; 00125 for (k=i;k<=m;++k) a[k*stridea+j] += f*a[k*stridea+i]; 00126 } 00127 } 00128 for (k=i;k<=m;++k) a[k*stridea+i] *= scale; 00129 } 00130 } 00131 w[i]=scale*g; 00132 g=s=scale=0.0; 00133 if (i <= m && i != n) { 00134 for (k=l;k<=n;++k) scale += fabs(a[i*stridea+k]); 00135 if (scale) { 00136 for (k=l;k<=n;++k) { 00137 a[i*stridea+k] /= scale; 00138 s += a[i*stridea+k]*a[i*stridea+k]; 00139 } 00140 f=a[i*stridea+l]; 00141 g = -SIGN(sqrt(s),f); 00142 h=f*g-s; 00143 a[i*stridea+l]=f-g; 00144 for (k=l;k<=n;k++) vec[k]=a[i*stridea+k]/h; 00145 if (i != m) { 00146 for (j=l;j<=m;++j) { 00147 for (s=0.0,k=l;k<=n;k++) s += a[j*stridea+k]*a[i*stridea+k]; 00148 for (k=l;k<=n;k++) a[j*stridea+k] += s*vec[k]; 00149 } 00150 } 00151 for (k=l;k<=n;++k) a[i*stridea+k] *= scale; 00152 } 00153 } 00154 maxarg1=anorm; 00155 maxarg2=(fabs(w[i])+fabs(vec[i])); 00156 anorm = maxarg1 > maxarg2 ? maxarg1 : maxarg2; 00157 } 00158 /* Accumulation of right-hand transformations. */ 00159 for (i=n;i>=1;--i) { 00160 if (i<n) { 00161 if (g) { 00162 for (j=l;j<=n;++j) v[j*stridev+i]=(a[i*stridea+j]/a[i*stridea+l])/g; 00163 for (j=l;j<=n;++j) { 00164 for (s=0.0,k=l;k<=n;++k) s += a[i*stridea+k]*v[k*stridev+j]; 00165 for (k=l;k<=n;++k) v[k*stridev+j] += s*v[k*stridev+i]; 00166 } 00167 } 00168 for (j=l;j<=n;++j) v[i*stridev+j]=v[j*stridev+i]=0.0; 00169 } 00170 v[i*stridev+i]=1.0; 00171 g=vec[i]; 00172 l=i; 00173 } 00174 /* Accumulation of left-hand transformations. */ 00175 for (i=n;i>=1;--i) { 00176 l=i+1; 00177 g=w[i]; 00178 if (i<n) for (j=l;j<=n;++j) a[i*stridea+j]=0.0; 00179 if (g) { 00180 g=1.0/g; 00181 if (i != n) { 00182 for (j=l;j<=n;++j) { 00183 for (s=0.0,k=l;k<=m;++k) s += a[k*stridea+i]*a[k*stridea+j]; 00184 f=(s/a[i*stridea+i])*g; 00185 for (k=i;k<=m;++k) a[k*stridea+j] += f*a[k*stridea+i]; 00186 } 00187 } 00188 for (j=i;j<=m;++j) a[j*stridea+i] *= g; 00189 } else { 00190 for (j=i;j<=m;++j) a[j*stridea+i]=0.0; 00191 } 00192 ++a[i*stridea+i]; 00193 } 00194 /* Diagonalization of the bidiagonal form. */ 00195 for (k=n;k>=1;--k) { /* Loop over singular values. */ 00196 for (its=1;its<=NrIts;its++) { /* Loop over allowed iterations. */ 00197 flag=1; 00198 for (l=k;l>=1;--l) { /* Test for splitting. */ 00199 nm=l-1; /* Note that vec[1] is always zero. */ 00200 if ((double)(fabs(vec[l])+anorm) == anorm) { 00201 flag=0; 00202 break; 00203 } 00204 if ((double)(fabs(w[nm])+anorm) == anorm) break; 00205 } 00206 if (flag) { 00207 c=0.0; /* Cancellation of vec[l], if l>1: */ 00208 s=1.0; 00209 for (i=l;i<=k;++i) { 00210 f=s*vec[i]; 00211 vec[i]=c*vec[i]; 00212 if ((double)(fabs(f)+anorm) == anorm) break; 00213 g=w[i]; 00214 w[i]=h=PYTHAG(f,g); 00215 h=1.0/h; 00216 c=g*h; 00217 s=(-f*h); 00218 for (j=1;j<=m;++j) { 00219 y=a[j*stridea+nm]; 00220 z=a[j*stridea+i]; 00221 a[j*stridea+nm]=y*c+z*s; 00222 a[j*stridea+i]=z*c-y*s; 00223 } 00224 } 00225 } 00226 z=w[k]; 00227 if (l == k) { /* Convergence. */ 00228 if (z <= 0.0) { /* Singular value is made nonnegative. */ 00229 w[k] = -z; 00230 for (j=1;j<=n;++j) v[j*stridev+k]=(-v[j*stridev+k]); 00231 } 00232 break; 00233 } 00234 x=w[l]; /* Shift from bottom 2-by-2 minor: */ 00235 nm=k-1; 00236 y=w[nm]; 00237 g=vec[nm]; 00238 h=vec[k]; 00239 f=((y-z)*(y+z)+(g-h)*(g+h))/(2.0*h*y); 00240 g=PYTHAG(f,1.0); 00241 f=((x-z)*(x+z)+h*((y/(f+SIGN(g,f)))-h))/x; 00242 /* Next QR transformation: */ 00243 c=s=1.0; 00244 for (j=l;j<=nm;++j) { 00245 i=j+1; 00246 g=vec[i]; 00247 y=w[i]; 00248 h=s*g; 00249 g=c*g; 00250 z=PYTHAG(f,h); 00251 vec[j]=z; 00252 c=f/z; 00253 s=h/z; 00254 f=x*c+g*s; 00255 g=g*c-x*s; 00256 h=y*s; 00257 y=y*c; 00258 for (jj=1;jj<=n;++jj) { 00259 x=v[jj*stridev+j]; 00260 z=v[jj*stridev+i]; 00261 v[jj*stridev+j]=x*c+z*s; 00262 v[jj*stridev+i]=z*c-x*s; 00263 } 00264 z=PYTHAG(f,h); 00265 w[j]=z; 00266 if (z) { 00267 z=1.0/z; 00268 c=f*z; 00269 s=h*z; 00270 } 00271 f=(c*g)+(s*y); 00272 x=(c*y)-(s*g); 00273 for (jj=1;jj<=m;++jj) { 00274 y=a[jj*stridea+j]; 00275 z=a[jj*stridea+i]; 00276 a[jj*stridea+j]=y*c+z*s; 00277 a[jj*stridea+i]=z*c-y*s; 00278 } 00279 } 00280 vec[l]=0.0; 00281 vec[k]=f; 00282 w[k]=x; 00283 } 00284 } 00285 if (its == NrIts) 00286 return (2); 00287 else 00288 return (0); 00289 } 00290 00291 00292 00293 00294 00295 00296 00297 00298 00299 00300 00301 00302 00303 00304 PseudoInverse::PseudoInverse(int _maxsize): 00305 maxsize(_maxsize) 00306 { 00307 tmp = new double[maxsize]; 00308 y2 = new double[maxsize]; 00309 S = new double[maxsize]; 00310 V = new double[maxsize*maxsize]; 00311 U = new double[maxsize*maxsize]; 00312 ndx = new int[maxsize]; 00313 strideV = maxsize; 00314 strideU = maxsize; 00315 prepared = false; 00316 } 00317 00318 PseudoInverse::~PseudoInverse() { 00319 delete[] ndx; 00320 delete[] U; 00321 delete[] V; 00322 delete[] S; 00323 delete[] y2; 00324 delete[] tmp; 00325 } 00326 00327 void PseudoInverse::inverse( 00328 const double* y, 00329 double* x, 00330 double eps) 00331 { 00332 assert( prepared ); 00333 00334 int i,j; 00335 double sum; 00336 00337 // tmp = (Si*U'*Ly*y), 00338 for (i=0;i<n;++i) { 00339 sum = 0.0; 00340 for (j=0;j<m;++j) { 00341 sum+= U[strideU*j+i]*Ly[j]*y[j]; 00342 } 00343 tmp[i] = sum*(fabs(S[i])<eps?0.0:1.0/S[i]); 00344 } 00345 // x = Lx^-1*V*tmp + x 00346 for (i=0;i<n;++i) { 00347 sum = 0.0; 00348 for (j=0;j<n;++j) { 00349 sum+=V[strideV*i+j]*tmp[j]; 00350 } 00351 x[i]=sum/Lx[i]; 00352 } 00353 } 00354 00355 00356 void PseudoInverse::inverseWithNullSpace( 00357 const double* y, 00358 double* x, 00359 const double* xd, 00360 double eps) 00361 { 00362 // uses y2 with size m 00363 int i,j; 00364 double sum; 00365 assert( prepared ); 00366 assert( (0 <=m)&&(m < maxsize)); 00367 assert( (0 <=n)&&(n < maxsize)); 00368 00369 // y2=y-A*xd; 00370 for (i=0;i<m;++i) { 00371 sum = 0.0; 00372 for (j=0;j<n;++j) { 00373 sum+= A[i*strideA+j]*xd[j]; 00374 } 00375 y2[i] = y[i]-sum; 00376 } 00377 inverse(y2,x,eps); 00378 00379 // x = x + xd 00380 for (i=0;i<n;++i) { 00381 x[i]+= xd[i]; 00382 } 00383 } 00384 00385 00386 class SVD_Ordering { 00387 const double* S; 00388 public: 00389 SVD_Ordering(const double *_S):S(_S) {} 00390 bool operator()(int i,int j) { 00391 return S[i]>S[j]; 00392 } 00393 }; 00394 00409 int PseudoInverse::prepare( 00410 const double* _A,int _strideA,int _m,int _n, 00411 const double *_Ly,const double* _Lx, 00412 int nrOfIts) { 00413 // uses tmp with size m for svdcmp 00414 // uses tmp with size n for matrix*vector multiplication 00415 int i,j; 00416 int result; 00417 m=_m; 00418 n=_n; 00419 A=_A; 00420 strideA=_strideA; 00421 Lx=_Lx; 00422 Ly=_Ly; 00423 assert( (0 <=m)&&(m < maxsize)); 00424 assert( (0 <=n)&&(n < maxsize)); 00425 00426 // copy A into U and if necessary, (m<n) fill with zeros 00427 // Dim U = max(m,n) x n 00428 // scale with the weight matrices 00429 // U = Ly*A*lx^-1 00430 for (i=0;i<m;i++) { 00431 for (j=0;j<n;j++) { 00432 U[strideU*i+j] = Ly[i]*A[strideA*i+j]/Lx[j]; 00433 } 00434 } 00435 for (i=m;i<n;i++) { 00436 for (j=0;j<n;j++) { 00437 U[strideU*i+j] = 0.0; 00438 } 00439 } 00440 int m2 = m < n ? n: m; 00441 result = svdcmp(U,strideU,m2,n,S,V,strideV,nrOfIts,tmp); 00442 prepared = (result==0); 00443 // PERFORM SORTING OF THE SVD TO OBTAIN AN INDEX : 00444 for (j=0;j<n;j++) ndx[j]=j; 00445 SVD_Ordering order(S); 00446 std::sort(ndx,ndx+n,order); 00447 return result; 00448 } 00449 00450 00451 int PseudoInverse::smallestSV(double eps) { 00452 assert(prepared); 00453 for (int i=n-1;i>=0;i--) { 00454 if (S[ndx[i]] >= eps) { 00455 return ndx[i]; 00456 } 00457 } 00458 return 0; 00459 } 00460 double PseudoInverse::derivsv( 00461 const double* Adot, 00462 int strideAdot, 00463 int svnr) 00464 { 00465 assert(prepared); 00466 int i,j; 00467 double sum; 00468 sum = 0.0; 00469 for (i=0;i<m;++i) { 00470 for (j=0;j<n;++j) { 00471 // sum += U[i,r]*Ly[i]*Adot[i,j]/Lx[j]*V[j,r] 00472 sum += U[strideU*i+svnr]*Ly[i]*Adot[strideAdot*i+j]/Lx[j]*V[strideV*j+svnr]; 00473 } 00474 } 00475 return sum; 00476 } 00477 00478 00479