factor.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006 are permitted provided that the following conditions are met:
00007 
00008 Redistributions of source code must retain the above copyright notice, this list of
00009 conditions and the following disclaimer. Redistributions in binary form must reproduce
00010 the above copyright notice, this list of conditions and the following disclaimer
00011 in the documentation and/or other materials provided with the distribution. 
00012 
00013 Neither the name of the Johns Hopkins University nor the names of its contributors
00014 may be used to endorse or promote products derived from this software without specific
00015 prior written permission. 
00016 
00017 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
00018 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES 
00019 OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
00020 SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00021 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
00022 TO, PROCUREMENT OF SUBSTITUTE  GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
00023 BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00025 ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00026 DAMAGE.
00027 */
00028 
00030 // Polynomial Roots //
00032 #include <math.h>
00033 #include <pcl/surface/3rdparty/poisson4/factor.h>
00034 
00035 namespace pcl
00036 {
00037   namespace poisson
00038   {
00039 
00040 
00041     int Factor(double a1,double a0,double roots[1][2],double EPS){
00042       if(fabs(a1)<=EPS){return 0;}
00043       roots[0][0]=-a0/a1;
00044       roots[0][1]=0;
00045       return 1;
00046     }
00047     int Factor(double a2,double a1,double a0,double roots[2][2],double EPS){
00048       double d;
00049       if(fabs(a2)<=EPS){return Factor(a1,a0,roots,EPS);}
00050 
00051       d=a1*a1-4*a0*a2;
00052       a1/=(2*a2);
00053       if(d<0){
00054         d=sqrt(-d)/(2*a2);
00055         roots[0][0]=roots[1][0]=-a1;
00056         roots[0][1]=-d;
00057         roots[1][1]= d;
00058       }
00059       else{
00060         d=sqrt(d)/(2*a2);
00061         roots[0][1]=roots[1][1]=0;
00062         roots[0][0]=-a1-d;
00063         roots[1][0]=-a1+d;
00064       }
00065       return 2;
00066     }
00067     // Solution taken from: http://mathworld.wolfram.com/CubicFormula.html
00068     // and http://www.csit.fsu.edu/~burkardt/f_src/subpak/subpak.f90
00069     int Factor(double a3,double a2,double a1,double a0,double roots[3][2],double EPS){
00070       double q,r,r2,q3;
00071 
00072       if(fabs(a3)<=EPS){return Factor(a2,a1,a0,roots,EPS);}
00073       a2/=a3;
00074       a1/=a3;
00075       a0/=a3;
00076 
00077       q=-(3*a1-a2*a2)/9;
00078       r=-(9*a2*a1-27*a0-2*a2*a2*a2)/54;
00079       r2=r*r;
00080       q3=q*q*q;
00081 
00082       if(r2<q3){
00083         double sqrQ=sqrt(q);
00084         double theta = acos ( r / (sqrQ*q) );
00085         double cTheta=cos(theta/3)*sqrQ;
00086         double sTheta=sin(theta/3)*sqrQ*SQRT_3/2;
00087         roots[0][1]=roots[1][1]=roots[2][1]=0;
00088         roots[0][0]=-2*cTheta;
00089         roots[1][0]=-2*(-cTheta*0.5-sTheta);
00090         roots[2][0]=-2*(-cTheta*0.5+sTheta);
00091       }
00092       else{
00093         double s1,s2,sqr=sqrt(r2-q3);
00094         double t;
00095         t=-r+sqr;
00096         if(t<0){s1=-pow(-t,1.0/3);}
00097         else{s1=pow(t,1.0/3);}
00098         t=-r-sqr;
00099         if(t<0){s2=-pow(-t,1.0/3);}
00100         else{s2=pow(t,1.0/3);}
00101         roots[0][1]=0;
00102         roots[0][0]=s1+s2;
00103         s1/=2;
00104         s2/=2;
00105         roots[1][0]= roots[2][0]=-s1-s2;
00106         roots[1][1]= SQRT_3*(s1-s2);
00107         roots[2][1]=-roots[1][1];
00108       }
00109       roots[0][0]-=a2/3;
00110       roots[1][0]-=a2/3;
00111       roots[2][0]-=a2/3;
00112       return 3;
00113     }
00114     double ArcTan2(double y,double x){
00115       /* This first case should never happen */
00116       if(y==0 && x==0){return 0;}
00117       if(x==0){
00118         if(y>0){return PI/2.0;}
00119         else{return -PI/2.0;}
00120       }
00121       if(x>=0){return atan(y/x);}
00122       else{
00123         if(y>=0){return atan(y/x)+PI;}
00124         else{return atan(y/x)-PI;}
00125       }
00126     }
00127     double Angle(const double in[2]){
00128       if((in[0]*in[0]+in[1]*in[1])==0.0){return 0;}
00129       else{return ArcTan2(in[1],in[0]);}
00130     }
00131     void Sqrt(const double in[2],double out[2]){
00132       double r=sqrt(sqrt(in[0]*in[0]+in[1]*in[1]));
00133       double a=Angle(in)*0.5;
00134       out[0]=r*cos(a);
00135       out[1]=r*sin(a);
00136     }
00137     void Add(const double in1[2],const double in2[2],double out[2]){
00138       out[0]=in1[0]+in2[0];
00139       out[1]=in1[1]+in2[1];
00140     }
00141     void Subtract(const double in1[2],const double in2[2],double out[2]){
00142       out[0]=in1[0]-in2[0];
00143       out[1]=in1[1]-in2[1];
00144     }
00145     void Multiply(const double in1[2],const double in2[2],double out[2]){
00146       out[0]=in1[0]*in2[0]-in1[1]*in2[1];
00147       out[1]=in1[0]*in2[1]+in1[1]*in2[0];
00148     }
00149     void Divide(const double in1[2],const double in2[2],double out[2]){
00150       double temp[2];
00151       double l=in2[0]*in2[0]+in2[1]*in2[1];
00152       temp[0]= in2[0]/l;
00153       temp[1]=-in2[1]/l;
00154       Multiply(in1,temp,out);
00155     }
00156     // Solution taken from: http://mathworld.wolfram.com/QuarticEquation.html
00157     // and http://www.csit.fsu.edu/~burkardt/f_src/subpak/subpak.f90
00158     int Factor(double a4,double a3,double a2,double a1,double a0,double roots[4][2],double EPS){
00159       double R[2],D[2],E[2],R2[2];
00160 
00161       if(fabs(a4)<EPS){return Factor(a3,a2,a1,a0,roots,EPS);}
00162       a3/=a4;
00163       a2/=a4;
00164       a1/=a4;
00165       a0/=a4;
00166 
00167       Factor(1.0,-a2,a3*a1-4.0*a0,-a3*a3*a0+4.0*a2*a0-a1*a1,roots,EPS);
00168 
00169       R2[0]=a3*a3/4.0-a2+roots[0][0];
00170       R2[1]=0;
00171       Sqrt(R2,R);
00172       if(fabs(R[0])>10e-8){
00173         double temp1[2],temp2[2];
00174         double p1[2],p2[2];
00175 
00176         p1[0]=a3*a3*0.75-2.0*a2-R2[0];
00177         p1[1]=0;
00178 
00179         temp2[0]=((4.0*a3*a2-8.0*a1-a3*a3*a3)/4.0);
00180         temp2[1]=0;
00181         Divide(temp2,R,p2);
00182 
00183         Add     (p1,p2,temp1);
00184         Subtract(p1,p2,temp2);
00185 
00186         Sqrt(temp1,D);
00187         Sqrt(temp2,E);
00188       }
00189       else{
00190         R[0]=R[1]=0;
00191         double temp1[2],temp2[2];
00192         temp1[0]=roots[0][0]*roots[0][0]-4.0*a0;
00193         temp1[1]=0;
00194         Sqrt(temp1,temp2);
00195         temp1[0]=a3*a3*0.75-2.0*a2+2.0*temp2[0];
00196         temp1[1]=                  2.0*temp2[1];
00197         Sqrt(temp1,D);
00198         temp1[0]=a3*a3*0.75-2.0*a2-2.0*temp2[0];
00199         temp1[1]=                 -2.0*temp2[1];
00200         Sqrt(temp1,E);
00201       }
00202 
00203       roots[0][0]=-a3/4.0+R[0]/2.0+D[0]/2.0;
00204       roots[0][1]=        R[1]/2.0+D[1]/2.0;
00205 
00206       roots[1][0]=-a3/4.0+R[0]/2.0-D[0]/2.0;
00207       roots[1][1]=        R[1]/2.0-D[1]/2.0;
00208 
00209       roots[2][0]=-a3/4.0-R[0]/2.0+E[0]/2.0;
00210       roots[2][1]=       -R[1]/2.0+E[1]/2.0;
00211 
00212       roots[3][0]=-a3/4.0-R[0]/2.0-E[0]/2.0;
00213       roots[3][1]=       -R[1]/2.0-E[1]/2.0;
00214       return 4;
00215     }
00216 
00217     int Solve(const double* eqns,const double* values,double* solutions,int dim){
00218       int i,j,eIndex;
00219       double v,m;
00220       int *index=new int[dim];
00221       int *set=new int[dim];
00222       double* myEqns=new double[dim*dim];
00223       double* myValues=new double[dim];
00224 
00225       for(i=0;i<dim*dim;i++){myEqns[i]=eqns[i];}
00226       for(i=0;i<dim;i++){
00227         myValues[i]=values[i];
00228         set[i]=0;
00229       }
00230       for(i=0;i<dim;i++){
00231         // Find the largest equation that has a non-zero entry in the i-th index
00232         m=-1;
00233         eIndex=-1;
00234         for(j=0;j<dim;j++){
00235           if(set[j]){continue;}
00236           if(myEqns[j*dim+i]!=0 && fabs(myEqns[j*dim+i])>m){
00237             m=fabs(myEqns[j*dim+i]);
00238             eIndex=j;
00239           }
00240         }
00241         if(eIndex==-1){
00242           delete[] index;
00243           delete[] myValues;
00244           delete[] myEqns;
00245           delete[] set;
00246           return 0;
00247         }
00248         // The position in which the solution for the i-th variable can be found
00249         index[i]=eIndex;
00250         set[eIndex]=1;
00251 
00252         // Normalize the equation
00253         v=myEqns[eIndex*dim+i];
00254         for(j=0;j<dim;j++){myEqns[eIndex*dim+j]/=v;}
00255         myValues[eIndex]/=v;
00256 
00257         // Subtract it off from everything else
00258         for(j=0;j<dim;j++){
00259           if(j==eIndex){continue;}
00260           double vv=myEqns[j*dim+i];
00261           for(int k=0;k<dim;k++){myEqns[j*dim+k]-=myEqns[eIndex*dim+k]*vv;}
00262           myValues[j]-=myValues[eIndex]*vv;
00263         }
00264       }
00265       for(i=0;i<dim;i++){solutions[i]=myValues[index[i]];}
00266       delete[] index;
00267       delete[] myValues;
00268       delete[] myEqns;
00269       delete[] set;
00270       return 1;
00271     }
00272   }
00273 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:56