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 namespace pcl
00031 {
00032 namespace poisson
00033 {
00034
00036
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057 template< int Degree > inline bool LeftOverlap( unsigned int depth , int offset )
00058 {
00059 offset <<= 1;
00060 if( Degree & 1 ) return (offset < 1+Degree) && (offset > -1-Degree );
00061 else return (offset < Degree) && (offset > -2-Degree );
00062 }
00063 template< int Degree > inline bool RightOverlap( unsigned int depth , int offset )
00064 {
00065 offset <<= 1;
00066 int r = 1<<(depth+1);
00067 if( Degree & 1 ) return (offset > 2-1-Degree) && (offset < 2+1+Degree );
00068 else return (offset > 2-2-Degree) && (offset < 2+ Degree );
00069 }
00070 template< int Degree > inline int ReflectLeft( unsigned int depth , int offset )
00071 {
00072 if( Degree&1 ) return -offset;
00073 else return -1-offset;
00074 }
00075 template< int Degree > inline int ReflectRight( unsigned int depth , int offset )
00076 {
00077 int r = 1<<(depth+1);
00078 if( Degree&1 ) return r -offset;
00079 else return r-1-offset;
00080 }
00081
00082 template< int Degree , class Real >
00083 BSplineData<Degree,Real>::BSplineData( void )
00084 {
00085 vvDotTable = dvDotTable = ddDotTable = NULL;
00086 valueTables = dValueTables = NULL;
00087 functionCount = sampleCount = 0;
00088 }
00089
00090 template< int Degree , class Real >
00091 BSplineData< Degree , Real >::~BSplineData(void)
00092 {
00093 if( functionCount )
00094 {
00095 if( vvDotTable ) delete[] vvDotTable;
00096 if( dvDotTable ) delete[] dvDotTable;
00097 if( ddDotTable ) delete[] ddDotTable;
00098
00099 if( valueTables ) delete[] valueTables;
00100 if( dValueTables ) delete[] dValueTables;
00101 }
00102 vvDotTable = dvDotTable = ddDotTable = NULL;
00103 valueTables = dValueTables=NULL;
00104 functionCount = 0;
00105 }
00106
00107 template<int Degree,class Real>
00108 void BSplineData<Degree,Real>::set( int maxDepth , bool useDotRatios , bool reflectBoundary )
00109 {
00110 this->useDotRatios = useDotRatios;
00111 this->reflectBoundary = reflectBoundary;
00112
00113 depth = maxDepth;
00114
00115 functionCount = BinaryNode< double >::CumulativeCenterCount( depth );
00116 sampleCount = BinaryNode< double >::CenterCount( depth ) + BinaryNode< double >::CornerCount( depth );
00117 baseFunctions = new PPolynomial<Degree>[functionCount];
00118 baseBSplines = new BSplineComponents[functionCount];
00119
00120 baseFunction = PPolynomial< Degree >::BSpline();
00121 for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( double(-(Degree+1)/2) + i - 0.5 );
00122 dBaseFunction = baseFunction.derivative();
00123 StartingPolynomial< Degree > sPolys[Degree+3];
00124
00125 for( int i=0 ; i<Degree+3 ; i++ )
00126 {
00127 sPolys[i].start = double(-(Degree+1)/2) + i - 1.5;
00128 sPolys[i].p *= 0;
00129 if( i<=Degree ) sPolys[i].p += baseBSpline[i ].shift( -1 );
00130 if( i>=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1];
00131 for( int j=0 ; j<i ; j++ ) sPolys[i].p -= sPolys[j].p;
00132 }
00133 leftBaseFunction.set( sPolys , Degree+3 );
00134 for( int i=0 ; i<Degree+3 ; i++ )
00135 {
00136 sPolys[i].start = double(-(Degree+1)/2) + i - 0.5;
00137 sPolys[i].p *= 0;
00138 if( i<=Degree ) sPolys[i].p += baseBSpline[i ];
00139 if( i>=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1].shift( 1 );
00140 for( int j=0 ; j<i ; j++ ) sPolys[i].p -= sPolys[j].p;
00141 }
00142 rightBaseFunction.set( sPolys , Degree+3 );
00143 dLeftBaseFunction = leftBaseFunction.derivative();
00144 dRightBaseFunction = rightBaseFunction.derivative();
00145 leftBSpline = rightBSpline = baseBSpline;
00146 leftBSpline [1] += leftBSpline[2].shift( -1 ) , leftBSpline[0] *= 0;
00147 rightBSpline[1] += rightBSpline[0].shift( 1 ) , rightBSpline[2] *= 0;
00148 double c , w;
00149 for( int i=0 ; i<functionCount ; i++ )
00150 {
00151 BinaryNode< double >::CenterAndWidth( i , c , w );
00152 baseFunctions[i] = baseFunction.scale(w).shift(c);
00153 baseBSplines[i] = baseBSpline.scale(w).shift(c);
00154 if( reflectBoundary )
00155 {
00156 int d , off , r;
00157 BinaryNode< double >::DepthAndOffset( i , d , off );
00158 r = 1<<d;
00159 if ( off==0 ) baseFunctions[i] = leftBaseFunction.scale(w).shift(c);
00160 else if( off==r-1 ) baseFunctions[i] = rightBaseFunction.scale(w).shift(c);
00161 if ( off==0 ) baseBSplines[i] = leftBSpline.scale(w).shift(c);
00162 else if( off==r-1 ) baseBSplines[i] = rightBSpline.scale(w).shift(c);
00163 }
00164 }
00165 }
00166 template<int Degree,class Real>
00167 void BSplineData<Degree,Real>::setDotTables( int flags )
00168 {
00169 clearDotTables( flags );
00170 int size = ( functionCount*functionCount + functionCount )>>1;
00171 int fullSize = functionCount*functionCount;
00172 if( flags & VV_DOT_FLAG )
00173 {
00174 vvDotTable = new Real[size];
00175 memset( vvDotTable , 0 , sizeof(Real)*size );
00176 }
00177 if( flags & DV_DOT_FLAG )
00178 {
00179 dvDotTable = new Real[fullSize];
00180 memset( dvDotTable , 0 , sizeof(Real)*fullSize );
00181 }
00182 if( flags & DD_DOT_FLAG )
00183 {
00184 ddDotTable = new Real[size];
00185 memset( ddDotTable , 0 , sizeof(Real)*size );
00186 }
00187 double vvIntegrals[Degree+1][Degree+1];
00188 double vdIntegrals[Degree+1][Degree ];
00189 double dvIntegrals[Degree ][Degree+1];
00190 double ddIntegrals[Degree ][Degree ];
00191 int vvSums[Degree+1][Degree+1];
00192 int vdSums[Degree+1][Degree ];
00193 int dvSums[Degree ][Degree+1];
00194 int ddSums[Degree ][Degree ];
00195 SetBSplineElementIntegrals< Degree , Degree >( vvIntegrals );
00196 SetBSplineElementIntegrals< Degree , Degree-1 >( vdIntegrals );
00197 SetBSplineElementIntegrals< Degree-1 , Degree >( dvIntegrals );
00198 SetBSplineElementIntegrals< Degree-1 , Degree-1 >( ddIntegrals );
00199
00200 for( int d1=0 ; d1<=depth ; d1++ )
00201 for( int off1=0 ; off1<(1<<d1) ; off1++ )
00202 {
00203 int ii = BinaryNode< Real >::CenterIndex( d1 , off1 );
00204 BSplineElements< Degree > b1( 1<<d1 , off1 , reflectBoundary ? BSplineElements<Degree>::NEUMANN : BSplineElements< Degree>::NONE );
00205 BSplineElements< Degree-1 > db1;
00206 b1.differentiate( db1 );
00207
00208 int start1 , end1;
00209
00210 start1 = -1;
00211 for( int i=0 ; i<int(b1.size()) ; i++ ) for( int j=0 ; j<=Degree ; j++ )
00212 {
00213 if( b1[i][j] && start1==-1 ) start1 = i;
00214 if( b1[i][j] ) end1 = i+1;
00215 }
00216 for( int d2=d1 ; d2<=depth ; d2++ )
00217 {
00218 for( int off2=0 ; off2<(1<<d2) ; off2++ )
00219 {
00220 int start2 = off2-Degree;
00221 int end2 = off2+Degree+1;
00222 if( start2>=end1 || start1>=end2 ) continue;
00223 start2 = std::max< int >( start1 , start2 );
00224 end2 = std::min< int >( end1 , end2 );
00225 if( d1==d2 && off2<off1 ) continue;
00226 int jj = BinaryNode< Real >::CenterIndex( d2 , off2 );
00227 BSplineElements< Degree > b2( 1<<d2 , off2 , reflectBoundary ? BSplineElements<Degree>::NEUMANN : BSplineElements< Degree>::NONE );
00228 BSplineElements< Degree-1 > db2;
00229 b2.differentiate( db2 );
00230
00231 int idx = SymmetricIndex( ii , jj );
00232 int idx1 = Index( ii , jj ) , idx2 = Index( jj , ii );
00233
00234 memset( vvSums , 0 , sizeof( int ) * ( Degree+1 ) * ( Degree+1 ) );
00235 memset( vdSums , 0 , sizeof( int ) * ( Degree+1 ) * ( Degree ) );
00236 memset( dvSums , 0 , sizeof( int ) * ( Degree ) * ( Degree+1 ) );
00237 memset( ddSums , 0 , sizeof( int ) * ( Degree ) * ( Degree ) );
00238 for( int i=start2 ; i<end2 ; i++ )
00239 {
00240 for( int j=0 ; j<=Degree ; j++ ) for( int k=0 ; k<=Degree ; k++ ) vvSums[j][k] += b1[i][j] * b2[i][k];
00241 for( int j=0 ; j<=Degree ; j++ ) for( int k=0 ; k< Degree ; k++ ) vdSums[j][k] += b1[i][j] * db2[i][k];
00242 for( int j=0 ; j< Degree ; j++ ) for( int k=0 ; k<=Degree ; k++ ) dvSums[j][k] += db1[i][j] * b2[i][k];
00243 for( int j=0 ; j< Degree ; j++ ) for( int k=0 ; k< Degree ; k++ ) ddSums[j][k] += db1[i][j] * db2[i][k];
00244 }
00245 double vvDot = 0 , dvDot = 0 , vdDot = 0 , ddDot = 0;
00246 for( int j=0 ; j<=Degree ; j++ ) for( int k=0 ; k<=Degree ; k++ ) vvDot += vvIntegrals[j][k] * vvSums[j][k];
00247 for( int j=0 ; j<=Degree ; j++ ) for( int k=0 ; k< Degree ; k++ ) vdDot += vdIntegrals[j][k] * vdSums[j][k];
00248 for( int j=0 ; j< Degree ; j++ ) for( int k=0 ; k<=Degree ; k++ ) dvDot += dvIntegrals[j][k] * dvSums[j][k];
00249 for( int j=0 ; j< Degree ; j++ ) for( int k=0 ; k< Degree ; k++ ) ddDot += ddIntegrals[j][k] * ddSums[j][k];
00250 vvDot /= (1<<d2);
00251 ddDot *= (1<<d2);
00252 vvDot /= ( b1.denominator * b2.denominator );
00253 dvDot /= ( b1.denominator * b2.denominator );
00254 vdDot /= ( b1.denominator * b2.denominator );
00255 ddDot /= ( b1.denominator * b2.denominator );
00256 if( fabs(vvDot)<1e-15 ) continue;
00257 if( flags & VV_DOT_FLAG ) vvDotTable [idx] = Real( vvDot );
00258 if( useDotRatios )
00259 {
00260 if( flags & DV_DOT_FLAG ) dvDotTable[idx1] = Real( dvDot / vvDot );
00261 if( flags & DV_DOT_FLAG ) dvDotTable[idx2] = Real( vdDot / vvDot );
00262 if( flags & DD_DOT_FLAG ) ddDotTable[idx ] = Real( ddDot / vvDot );
00263 }
00264 else
00265 {
00266 if( flags & DV_DOT_FLAG ) dvDotTable[idx1] = Real( dvDot );
00267 if( flags & DV_DOT_FLAG ) dvDotTable[idx2] = Real( dvDot );
00268 if( flags & DD_DOT_FLAG ) ddDotTable[idx ] = Real( ddDot );
00269 }
00270 }
00271 BSplineElements< Degree > b;
00272 b = b1;
00273 b.upSample( b1 );
00274 b1.differentiate( db1 );
00275 start1 = -1;
00276 for( int i=0 ; i<int(b1.size()) ; i++ ) for( int j=0 ; j<=Degree ; j++ )
00277 {
00278 if( b1[i][j] && start1==-1 ) start1 = i;
00279 if( b1[i][j] ) end1 = i+1;
00280 }
00281 }
00282 }
00283 }
00284 template<int Degree,class Real>
00285 void BSplineData<Degree,Real>::clearDotTables( int flags )
00286 {
00287 if( (flags & VV_DOT_FLAG) && vvDotTable ) delete[] vvDotTable , vvDotTable = NULL;
00288 if( (flags & DV_DOT_FLAG) && dvDotTable ) delete[] dvDotTable , dvDotTable = NULL;
00289 if( (flags & DD_DOT_FLAG) && ddDotTable ) delete[] ddDotTable , ddDotTable = NULL;
00290 }
00291 template< int Degree , class Real >
00292 void BSplineData< Degree , Real >::setSampleSpan( int idx , int& start , int& end , double smooth ) const
00293 {
00294 int d , off , res;
00295 BinaryNode< double >::DepthAndOffset( idx , d , off );
00296 res = 1<<d;
00297 double _start = ( off + 0.5 - 0.5*(Degree+1) ) / res - smooth;
00298 double _end = ( off + 0.5 + 0.5*(Degree+1) ) / res + smooth;
00299
00300
00301
00302 start = int( floor( _start * (sampleCount-1) + 1 ) );
00303 if( start<0 ) start = 0;
00304
00305
00306
00307 end = int( ceil( _end * (sampleCount-1) - 1 ) );
00308 if( end>=sampleCount ) end = sampleCount-1;
00309 }
00310 template<int Degree,class Real>
00311 void BSplineData<Degree,Real>::setValueTables( int flags , double smooth )
00312 {
00313 clearValueTables();
00314 if( flags & VALUE_FLAG ) valueTables = new Real[functionCount*sampleCount];
00315 if( flags & D_VALUE_FLAG ) dValueTables = new Real[functionCount*sampleCount];
00316 PPolynomial<Degree+1> function;
00317 PPolynomial<Degree> dFunction;
00318 for( int i=0 ; i<functionCount ; i++ )
00319 {
00320 if(smooth>0)
00321 {
00322 function = baseFunctions[i].MovingAverage(smooth);
00323 dFunction = baseFunctions[i].derivative().MovingAverage(smooth);
00324 }
00325 else
00326 {
00327 function = baseFunctions[i];
00328 dFunction = baseFunctions[i].derivative();
00329 }
00330 for( int j=0 ; j<sampleCount ; j++ )
00331 {
00332 double x=double(j)/(sampleCount-1);
00333 if(flags & VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));}
00334 if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));}
00335 }
00336 }
00337 }
00338 template<int Degree,class Real>
00339 void BSplineData<Degree,Real>::setValueTables(int flags,double valueSmooth,double normalSmooth){
00340 clearValueTables();
00341 if(flags & VALUE_FLAG){ valueTables=new Real[functionCount*sampleCount];}
00342 if(flags & D_VALUE_FLAG){dValueTables=new Real[functionCount*sampleCount];}
00343 PPolynomial<Degree+1> function;
00344 PPolynomial<Degree> dFunction;
00345 for(int i=0;i<functionCount;i++){
00346 if(valueSmooth>0) { function=baseFunctions[i].MovingAverage(valueSmooth);}
00347 else { function=baseFunctions[i];}
00348 if(normalSmooth>0) {dFunction=baseFunctions[i].derivative().MovingAverage(normalSmooth);}
00349 else {dFunction=baseFunctions[i].derivative();}
00350
00351 for(int j=0;j<sampleCount;j++){
00352 double x=double(j)/(sampleCount-1);
00353 if(flags & VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));}
00354 if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));}
00355 }
00356 }
00357 }
00358
00359
00360 template<int Degree,class Real>
00361 void BSplineData<Degree,Real>::clearValueTables(void){
00362 if( valueTables){delete[] valueTables;}
00363 if(dValueTables){delete[] dValueTables;}
00364 valueTables=dValueTables=NULL;
00365 }
00366
00367 template<int Degree,class Real>
00368 inline int BSplineData<Degree,Real>::Index( int i1 , int i2 ) const { return i1*functionCount+i2; }
00369 template<int Degree,class Real>
00370 inline int BSplineData<Degree,Real>::SymmetricIndex( int i1 , int i2 )
00371 {
00372 if( i1>i2 ) return ((i1*i1+i1)>>1)+i2;
00373 else return ((i2*i2+i2)>>1)+i1;
00374 }
00375 template<int Degree,class Real>
00376 inline int BSplineData<Degree,Real>::SymmetricIndex( int i1 , int i2 , int& index )
00377 {
00378 if( i1<i2 )
00379 {
00380 index = ((i2*i2+i2)>>1)+i1;
00381 return 1;
00382 }
00383 else
00384 {
00385 index = ((i1*i1+i1)>>1)+i2;
00386 return 0;
00387 }
00388 }
00389
00390
00392
00394 template< int Degree >
00395 BSplineElements< Degree >::BSplineElements( int res , int offset , int boundary )
00396 {
00397 denominator = 1;
00398 this->resize( res , BSplineElementCoefficients<Degree>() );
00399
00400 for( int i=0 ; i<=Degree ; i++ )
00401 {
00402 int idx = -_off + offset + i;
00403 if( idx>=0 && idx<res ) (*this)[idx][i] = 1;
00404 }
00405 if( boundary!=0 )
00406 {
00407 _addLeft( offset-2*res , boundary ) , _addRight( offset+2*res , boundary );
00408 if( Degree&1 ) _addLeft( offset-res , boundary ) , _addRight( offset+res , boundary );
00409 else _addLeft( -offset-1 , boundary ) , _addRight( -offset-1+2*res , boundary );
00410 }
00411 }
00412 template< int Degree >
00413 void BSplineElements< Degree >::_addLeft( int offset , int boundary )
00414 {
00415 int res = int( this->size() );
00416 bool set = false;
00417 for( int i=0 ; i<=Degree ; i++ )
00418 {
00419 int idx = -_off + offset + i;
00420 if( idx>=0 && idx<res ) (*this)[idx][i] += boundary , set = true;
00421 }
00422 if( set ) _addLeft( offset-2*res , boundary );
00423 }
00424 template< int Degree >
00425 void BSplineElements< Degree >::_addRight( int offset , int boundary )
00426 {
00427 int res = int( this->size() );
00428 bool set = false;
00429 for( int i=0 ; i<=Degree ; i++ )
00430 {
00431 int idx = -_off + offset + i;
00432 if( idx>=0 && idx<res ) (*this)[idx][i] += boundary , set = true;
00433 }
00434 if( set ) _addRight( offset+2*res , boundary );
00435 }
00436 template< int Degree >
00437 void BSplineElements< Degree >::upSample( BSplineElements< Degree >& high ) const
00438 {
00439 fprintf( stderr , "[ERROR] B-spline up-sampling not supported for degree %d\n" , Degree );
00440 exit( 0 );
00441 }
00442 template<>
00443 void BSplineElements< 1 >::upSample( BSplineElements< 1 >& high ) const
00444 {
00445 high.resize( size()*2 );
00446 high.assign( high.size() , BSplineElementCoefficients<1>() );
00447 for( int i=0 ; i<int(size()) ; i++ )
00448 {
00449 high[2*i+0][0] += 1 * (*this)[i][0];
00450 high[2*i+0][1] += 0 * (*this)[i][0];
00451 high[2*i+1][0] += 2 * (*this)[i][0];
00452 high[2*i+1][1] += 1 * (*this)[i][0];
00453
00454 high[2*i+0][0] += 1 * (*this)[i][1];
00455 high[2*i+0][1] += 2 * (*this)[i][1];
00456 high[2*i+1][0] += 0 * (*this)[i][1];
00457 high[2*i+1][1] += 1 * (*this)[i][1];
00458 }
00459 high.denominator = denominator * 2;
00460 }
00461 template<>
00462 void BSplineElements< 2 >::upSample( BSplineElements< 2 >& high ) const
00463 {
00464
00465
00466
00467
00468
00469
00470 high.resize( size()*2 );
00471 high.assign( high.size() , BSplineElementCoefficients<2>() );
00472 for( int i=0 ; i<int(size()) ; i++ )
00473 {
00474 high[2*i+0][0] += 1 * (*this)[i][0];
00475 high[2*i+0][1] += 0 * (*this)[i][0];
00476 high[2*i+0][2] += 0 * (*this)[i][0];
00477 high[2*i+1][0] += 3 * (*this)[i][0];
00478 high[2*i+1][1] += 1 * (*this)[i][0];
00479 high[2*i+1][2] += 0 * (*this)[i][0];
00480
00481 high[2*i+0][0] += 3 * (*this)[i][1];
00482 high[2*i+0][1] += 3 * (*this)[i][1];
00483 high[2*i+0][2] += 1 * (*this)[i][1];
00484 high[2*i+1][0] += 1 * (*this)[i][1];
00485 high[2*i+1][1] += 3 * (*this)[i][1];
00486 high[2*i+1][2] += 3 * (*this)[i][1];
00487
00488 high[2*i+0][0] += 0 * (*this)[i][2];
00489 high[2*i+0][1] += 1 * (*this)[i][2];
00490 high[2*i+0][2] += 3 * (*this)[i][2];
00491 high[2*i+1][0] += 0 * (*this)[i][2];
00492 high[2*i+1][1] += 0 * (*this)[i][2];
00493 high[2*i+1][2] += 1 * (*this)[i][2];
00494 }
00495 high.denominator = denominator * 4;
00496 }
00497
00498 template< int Degree >
00499 void BSplineElements< Degree >::differentiate( BSplineElements< Degree-1 >& d ) const
00500 {
00501 d.resize( this->size() );
00502 d.assign( d.size() , BSplineElementCoefficients< Degree-1 >() );
00503 for( int i=0 ; i<int(this->size()) ; i++ ) for( int j=0 ; j<=Degree ; j++ )
00504 {
00505 if( j-1>=0 ) d[i][j-1] -= (*this)[i][j];
00506 if( j<Degree ) d[i][j ] += (*this)[i][j];
00507 }
00508 d.denominator = denominator;
00509 }
00510
00511
00512 template< int Degree1 , int Degree2 >
00513 void SetBSplineElementIntegrals( double integrals[Degree1+1][Degree2+1] )
00514 {
00515 for( int i=0 ; i<=Degree1 ; i++ )
00516 {
00517 Polynomial< Degree1 > p1 = Polynomial< Degree1 >::BSplineComponent( i );
00518 for( int j=0 ; j<=Degree2 ; j++ )
00519 {
00520 Polynomial< Degree2 > p2 = Polynomial< Degree2 >::BSplineComponent( j );
00521 integrals[i][j] = ( p1 * p2 ).integral( 0 , 1 );
00522 }
00523 }
00524 }
00525
00526
00527 }
00528 }