EstimateDiameter.cpp
Go to the documentation of this file.
00001 // ========================================================================================
00002 //  ApproxMVBB
00003 //  Copyright (C) 2014 by Gabriel Nützi <nuetzig (at) imes (d0t) mavt (d0t) ethz (døt) ch>
00004 //
00005 //  This Source Code Form is subject to the terms of the Mozilla Public
00006 //  License, v. 2.0. If a copy of the MPL was not distributed with this
00007 //  file, You can obtain one at http://mozilla.org/MPL/2.0/.
00008 // ========================================================================================
00009 
00010 #include <limits>
00011 
00012 #include "ApproxMVBB/Config/Config.hpp"
00013 #include ApproxMVBB_TypeDefs_INCLUDE_FILE
00014 
00015 #include "ApproxMVBB/Diameter/EstimateDiameter.hpp"
00016 
00017 
00018 
00019 // Implementation ===============================================
00020 
00021 #include "ApproxMVBB/Diameter/Utils/alloc.hpp"
00022 #include "ApproxMVBB/Diameter/Utils/util.hpp"
00023 
00024 namespace ApproxMVBB
00025 {
00026 
00027 double DiameterEstimator::estimateDiameter(
00028         Diameter::TypeSegment *theDiam,
00029         double const**theList,
00030         const int first,
00031         const int last,
00032         const int dim,
00033         double epsilon)
00034 {
00035     using namespace Diameter;
00036     _SetReductionModeInIterative( 0 );
00037     _SetReductionModeOfDiameter( 0 );
00038     _SetReductionModeOfDbleNorm( 0 );
00039     _DoNotTryToReduceQ();
00040     return this->estimateDiameterInOneList(theDiam,theList,first,last,dim, epsilon);
00041 }
00042 
00043 double DiameterEstimator::estimateDiameterInOneList(
00044         Diameter::TypeSegment *theDiam,
00045         double const**theList,
00046         const int first,
00047         const int last,
00048         const int dim,
00049         double _epsilon_  )
00050 {
00051 
00052     using namespace Diameter;
00053 
00054     int index;
00055 
00056     int f=first;
00057     int l=last;
00058 
00059     int newEstimateIsSmallerThanCurrentEstimate;
00060     TypeSegment theSeg;
00061 
00062     TypeListOfSegments theDoubleNormals;
00063 
00064     double newEstimate;
00065 
00066     int newlast;
00067 
00068 
00069     int verboseWhenReducing     = _GetVerboseWhenReducing();
00070     int _reduction_mode_in_iterative_ = _GetReductionModeInIterative();
00071     int tryToReduceQ            = _GetTryToReduceQ();
00072     int _reduction_mode_of_diameter_ = _GetReductionModeOfDiameter();
00073     int _reduction_mode_of_dbleNorm_ = _GetReductionModeOfDbleNorm();
00074     int _Q_scan_                     = _GetQscan();
00075     int _tight_bounds_               = _GetTightBounds();
00076 
00077     int i, j, k, n;
00078     int index1, index2;
00079 
00080     int suspicion_of_convex_hull = 0; // not used
00081     int fdn, ldn, idn;
00082 
00083     double epsilon = _epsilon_;
00084     double bound, upperBound = 0.0;
00085 
00086     double upperSquareDiameter = 0.0;
00087 
00088     theDoubleNormals.n = 0;
00089     theDoubleNormals.nalloc = 0;
00090     theDoubleNormals.seg = NULL;
00091 
00092     theDiam->extremity1 = (double*)NULL;
00093     theDiam->extremity2 = (double*)NULL;
00094     theDiam->squareDiameter = std::numeric_limits<double>::lowest();
00095 
00096     if ( first < 0 || last < 0 ) return( -1.0 );
00097     if ( first > last )
00098     {
00099         l = first;
00100         f = last;
00101     }
00102     if ( f == l )
00103     {
00104         theDiam->extremity1 = theList[f];
00105         theDiam->extremity2 = theList[l];
00106         return( 0.0 );
00107     }
00108 
00109     index = getRandomInt( f, l );
00110     do
00111     {
00112 
00113         /* end conditions
00114          */
00115         newEstimateIsSmallerThanCurrentEstimate = 0;
00116 
00117         /* find a double normal
00118          */
00119         newEstimate = _MaximalSegmentInOneList( &theSeg, index, theList, &f, &l, dim );
00120 
00121         /* if we get a better estimation
00122          */
00123         if ( newEstimate > theDiam->squareDiameter )
00124         {
00125 
00126             /* update variables
00127              */
00128             *theDiam = theSeg;
00129 
00130             /* keep the maximal segment in list
00131              */
00132             if ( _AddSegmentToList( &theSeg, &theDoubleNormals ) != 1 )
00133             {
00134                 if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00135                 return( -1.0 );
00136             }
00137 
00138 
00139             /* find the farthest point outside the sphere
00140              */
00141             newlast = l;
00142             index = _FarthestPointFromSphere( &theSeg, theList,
00143                     f, &newlast, dim,
00144                     _reduction_mode_in_iterative_ );
00145             if ( _reduction_mode_in_iterative_ == 1 )
00146             {
00147                 if ( verboseWhenReducing )
00148                     //fprintf( stdout, "...processing frth: remove %d points\n", l-newlast );
00149                     if ( newlast == l )
00150                     {
00151                         suspicion_of_convex_hull = 1;
00152                         _reduction_mode_of_diameter_ = 0;
00153                         _reduction_mode_of_dbleNorm_ = 0;
00154                     }
00155                 l = newlast;
00156             }
00157 
00158             /* stopping condition
00159             no point outside the sphere
00160             */
00161             if ( index < f )
00162             {
00163                 if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00164                 return( theDiam->squareDiameter );
00165             }
00166 
00167             /* other stopping condition
00168 
00169             the farthest point M outside the sphere
00170             is not that far away with a ball of diameter AB (and center C)
00171 
00172             we have MA.MB = MC^2 - |AB|^2 / 4
00173             leading to 4 * MC^2 = 4 * MA.MB + |AB|^2
00174 
00175             an upper bound of the diameter is then 2 MC
00176             thus (4 * MA.MB + |AB|^2) is a squared upper bound of the diameter
00177             */
00178 
00179             bound = 4.0 * _ScalarProduct( theList[index], theDiam->extremity1,
00180                     theList[index], theDiam->extremity2, dim ) +
00181                     theDiam->squareDiameter;
00182 
00183             /* stopping condition
00184 
00185             we want 2*MC < (1+epsilon) * d_estimate
00186                                         d_estimate = |AB|
00187 
00188             4 * MC^2                       < (1+epsilon)^2 * (d_estimate)^2
00189             4 * MA.MB + (d_estimate)^2     < (1+epsilon)^2 * (d_estimate)^2
00190             1 + 4 * MA.MB / (d_estimate)^2 < (1+epsilon)^2
00191 
00192             */
00193             if ( 1.0 + 4.0 * _ScalarProduct( theList[index], theDiam->extremity1,
00194                     theList[index], theDiam->extremity2, dim ) /
00195                     theDiam->squareDiameter < ( 1.0 + epsilon ) * ( 1.0 + epsilon ) )
00196             {
00197                 if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00198                 return( bound ) ;
00199             }
00200 
00201         }
00202         else
00203         {
00204 
00205             newEstimateIsSmallerThanCurrentEstimate = 1;
00206 
00207             /*  I add the found segment to the list
00208             there is no evidence that it is a maximal segment for
00209             the initial set P (but it is for the current one
00210             ie the initial minus the points which have been removed),
00211             it may somehow help in case of reduction of the set
00212             of potential extremities
00213 
00214 
00215             The list of double normals is sorted (from 0 to n)
00216             by increasing square diameter:
00217             - the best diameter is added (again) at the end
00218             - we search the right place for this new element
00219 
00220             */
00221 
00222             if ( _AddSegmentToList( theDiam, &theDoubleNormals ) != 1 )
00223             {
00224                 if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00225                 return( -1.0 );
00226             }
00227 
00228             for ( n = theDoubleNormals.n-2; n >= 0 ; n-- )
00229             {
00230                 if ( n == 0 )
00231                 {
00232                     theDoubleNormals.seg[ n ] = theSeg;
00233                 }
00234                 else
00235                 {
00236                     if ( theSeg.squareDiameter <= theDoubleNormals.seg[ n ].squareDiameter &&
00237                             theSeg.squareDiameter >  theDoubleNormals.seg[ n-1 ].squareDiameter )
00238                     {
00239                         theDoubleNormals.seg[ n ] = theSeg;
00240                         n = -1;
00241                     }
00242                     else
00243                     {
00244                         theDoubleNormals.seg[ n ] = theDoubleNormals.seg[ n-1 ];
00245                     }
00246                 }
00247             }
00248 
00249         }
00250 
00251     }
00252     while ( newEstimateIsSmallerThanCurrentEstimate == 0 );
00253 
00254 
00255     /* last processing with the found diameter
00256        - points inside the smallest sphere of the
00257          diameter may have been already removed
00258      */
00259     if ( _reduction_mode_in_iterative_ > 0 && _reduction_mode_of_diameter_ == 1 )
00260         _reduction_mode_of_diameter_ = 0;
00261 
00262     newlast = l;
00263     index = _LastPointOutsideSphereWithDiameter( theDiam, theDiam->squareDiameter,
00264             theList, f, &newlast, dim,
00265             _reduction_mode_of_diameter_ );
00266     if ( _reduction_mode_of_diameter_ == 1 ||
00267             _reduction_mode_of_diameter_ == 2 )
00268     {
00269         if ( verboseWhenReducing )
00270             //fprintf( stdout, "...processing diam: remove %d points\n", l-newlast );
00271             if ( newlast == l )
00272             {
00273                 suspicion_of_convex_hull = 1;
00274                 _reduction_mode_of_dbleNorm_ = 0;
00275             }
00276         l = newlast;
00277     }
00278 
00279 
00280     /* in some (rare) case, the remaining points outside the largest
00281        sphere are removed while searching for a better diameter
00282        thus it is still an avantageous case.
00283        if any, we have
00284        #f       -> #index : points outside the sphere
00285        #index+1 -> #l     : points inside the sphere
00286     */
00287     if ( index < f )
00288     {
00289         if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00290         return( theDiam->squareDiameter );
00291     }
00292 
00293     /* do you have enough precision?
00294      */
00295     index2 = index;
00296     upperSquareDiameter = theDiam->squareDiameter * (1.0 + epsilon) * (1.0 + epsilon);
00297 
00298 
00299     index1  = _LastPointOutsideSphereWithDiameter( theDiam, upperSquareDiameter,
00300             theList, f, &index2, dim, 0 );
00301     /* there is no points outside the sphere of diameter d * (1 + epsilon)
00302        find the farthest one to get a better upper bound of the diameter
00303     */
00304     if ( index1 < f )
00305     {
00306         if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00307 
00308         upperBound = 4.0 * _ScalarProduct( theList[f], theDiam->extremity1,
00309                 theList[f], theDiam->extremity2, dim ) +
00310                 theDiam->squareDiameter;
00311 
00312         for ( k=f+1; k<=index2; k++ )
00313         {
00314             bound = 4.0 * _ScalarProduct( theList[k], theDiam->extremity1,
00315                     theList[k], theDiam->extremity2, dim ) +
00316                     theDiam->squareDiameter;
00317             if ( upperBound < bound ) upperBound = bound;
00318         }
00319         return( upperBound );
00320     }
00321 
00322     /* get an upper bound of the diameter with points in [#index1+1 -> #index2]
00323        if there are points in this interval
00324        else the upper bound is simply d
00325 
00326        we have
00327        #f        -> #index1 : points outside the sphere of diameter d (1+epsilon)
00328        #index1+1 -> #index2 : points outside the sphere but inside the previous one
00329        #index2+1 -> #l      : points inside the sphere
00330     */
00331     if ( _tight_bounds_ )
00332     {
00333         upperBound = theDiam->squareDiameter;
00334         if ( index1 < index2 )
00335         {
00336             for ( k=index1+1; k<=index2; k++ )
00337             {
00338                 bound = 4.0 * _ScalarProduct( theList[k], theDiam->extremity1,
00339                         theList[k], theDiam->extremity2, dim ) +
00340                         theDiam->squareDiameter;
00341                 if ( upperBound < bound ) upperBound = bound;
00342             }
00343         }
00344     }
00345     else
00346     {
00347         upperBound = upperSquareDiameter;
00348     }
00349 
00350     /* to get some information on
00351        the points
00352     */
00353     if ( 0 )
00354     {
00355         for ( n = theDoubleNormals.n-1; n >= 0; n -- )
00356         {
00357             /*_CountPointsInSpheres( &theDoubleNormals.seg[ n ], theDiam->squareDiameter,
00358                     theList, f, l, dim );*/
00359         }
00360     }
00361 
00362     /* here we will reduce the set of potential extremities
00363        for the diameter,
00364        ie the set of points which are to be compared against all
00365        the other points
00366 
00367        right now, we have
00368        #f        -> #index1 : points outside the sphere of diameter d+epsilon
00369        #index1+1 -> #index2 : points outside the sphere of diameter d
00370        #index2+1 -> #l      : points inside the sphere
00371 
00372        we have a set of maximal segments
00373        theDoubleNormals.seg[ #i ] for #i from 0 to theDoubleNormals.n-1
00374        with
00375        theDoubleNormals.seg[ theDoubleNormals.n-1 ] == theDiam
00376 
00377     */
00378     index = index1;
00379     /* right now, we have
00380        #f       -> #index : points outside the sphere of diameter d*(1+epsilon)
00381        #index+1 -> #l     : points inside the sphere of diameter d*(1+epsilon)
00382     */
00383 
00384     if ( tryToReduceQ && theDoubleNormals.n > 1 )
00385     {
00386 
00387         for ( k = 0; k < theDoubleNormals.n; k ++ )
00388             theDoubleNormals.seg[k].reduction_mode = _reduction_mode_of_dbleNorm_;
00389 
00390         switch ( _Q_scan_ )
00391         {
00392         default :
00393         case 0 :
00394             /* backward
00395              */
00396             ldn = 0;
00397             fdn = theDoubleNormals.n-2;
00398             idn = -1;
00399             break;
00400         case 1 :
00401             /* forward
00402              */
00403             fdn = 0;
00404             ldn = theDoubleNormals.n-2;
00405             idn = +1;
00406             break;
00407         }
00408 
00409         for ( n = fdn; n != (ldn+idn) && index >= f ; n += idn )
00410         {
00411 
00412             /* in [ #f #index ] find the points outside the sphere
00413             theDoubleNormals.seg[ n ]
00414 
00415             as a result
00416             #f   -> #i     are to be compared with all other points
00417             #i+1 -> #index are to be compared with a subset
00418                           if this subset is empty, continue
00419 
00420             */
00421             i = _LastPointOutsideSphereWithDiameter( &theDoubleNormals.seg[ n ],
00422                     upperSquareDiameter,
00423                     theList, f, &index, dim, 0 );
00424             if ( i >= index ) continue;
00425 
00426 
00427             /* remise a jour de l'upper bound,
00428             a partir des points de [#i+1     -> #index]
00429             par rapport a la double normale courante
00430 
00431             Ce sont des points qui etaient candidats parce qu'au
00432             dela de la precision demandee, mais qui sont maintenant en
00433             deca de celle-ci pour la double normale courante,
00434             donc on reste en deca de la precision, par contre je ne sais
00435             s'il faut toujours mettre a jour la borne sup ...
00436 
00437             */
00438             if ( _tight_bounds_ )
00439             {
00440                 for ( k = i+1; k <= index; k++ )
00441                 {
00442                     bound = 4.0 * _ScalarProduct( theList[k], theDoubleNormals.seg[ n ].extremity1,
00443                             theList[k], theDoubleNormals.seg[ n ].extremity2, dim ) +
00444                             theDoubleNormals.seg[ n ].squareDiameter;
00445                     if ( upperBound < bound ) upperBound = bound;
00446                 }
00447             }
00448 
00449 
00450 
00451             /* in [ #index+1 #l ] find the points outside the sphere
00452             theDoubleNormals.seg[ n ]
00453 
00454             as a result
00455             #index+1 -> #j   are to be compared with the previous subset
00456             */
00457 
00458             newlast = l;
00459 
00460             if ( _tight_bounds_ )
00461             {
00462                 j = _LastPointOutsideSphereAndBoundWithDiameter( &theDoubleNormals.seg[ n ],
00463                         upperSquareDiameter,
00464                         theList, index+1, &newlast, dim,
00465                         theDoubleNormals.seg[ n ].reduction_mode,
00466                         &bound );
00467                 if ( upperBound < bound ) upperBound = bound;
00468             }
00469             else
00470             {
00471                 j = _LastPointOutsideSphereWithDiameter( &theDoubleNormals.seg[ n ],
00472                         upperSquareDiameter,
00473                         theList, index+1, &newlast, dim,
00474                         theDoubleNormals.seg[ n ].reduction_mode );
00475             }
00476 
00477             if ( theDoubleNormals.seg[ n ].reduction_mode == 1 ||
00478                     theDoubleNormals.seg[ n ].reduction_mode == 2 )
00479             {
00480 
00481                 if ( verboseWhenReducing )
00482                     //fprintf( stdout, "...processing dbNR: remove %d points\n", l-newlast );
00483                     if ( newlast == l )
00484                     {
00485                         suspicion_of_convex_hull = 1;
00486                         for ( k = 0; k < theDoubleNormals.n; k ++ )
00487                             theDoubleNormals.seg[k].reduction_mode = 0;
00488                     }
00489                 l = newlast;
00490             }
00491 
00492             if ( j <= index )
00493             {
00494                 index = i;
00495                 continue;
00496             }
00497 
00498             /* right now
00499             #f       -> #i     : points to be compared with all other points
00500             #i+1     -> #index : points to be compared with the below set
00501             #index+1 -> #j     : points to be compared with the above set
00502             #j+1     -> #l     : remaining points
00503 
00504             */
00505 
00506             theSeg.extremity1 = (double*)NULL;
00507             theSeg.extremity2 = (double*)NULL;
00508             theSeg.squareDiameter = 0.0;
00509 
00510 
00511             newEstimate = _QuadraticDiameterInTwoLists( &theSeg, NULL, NULL,
00512                     theList, i+1, index,
00513                     theList, index+1, j,
00514                     dim );
00515 
00516 
00517 
00518 
00519             if ( newEstimate > theDiam->squareDiameter )
00520             {
00521                 /* update variables
00522                  */
00523                 *theDiam = theSeg;
00524                 if ( upperBound < newEstimate ) upperBound = newEstimate;
00525                 if ( upperSquareDiameter < newEstimate ) upperSquareDiameter = newEstimate;
00526                 /* we find a better estimate
00527                    it is perhaps not the diameter, according that one
00528                    diameter extremity can be in [ #f #i ]
00529                    The question are :
00530                    1. have we to look for a maximal segment with these two points
00531                       or not ?
00532                       -> Seems not necessary ...
00533                    2. have we to consider this segment with the others ?
00534                       -> yes
00535                          but we can not reduce the whole set with it !!!
00536                 */
00537                 theDoubleNormals.seg[ n ] = theSeg;
00538                 theDoubleNormals.seg[ n ].reduction_mode = 0;
00539                 n -= idn;
00540             }
00541 
00542 
00543             /* Q is now reduced
00544              */
00545             index = i;
00546 
00547         }
00548     }
00549 
00550     if ( theDoubleNormals.nalloc > 0 ) free( theDoubleNormals.seg );
00551 
00552     /* exhautive search
00553 
00554        comparison of points from #f to #index
00555        against all others points
00556     */
00557 
00558     if ( dim == 2 )
00559     {
00560         for ( i=f;   i<=index; i++ )
00561             for ( j=i+1; j<=l;     j++ )
00562             {
00563                 newEstimate = _SquareDistance2D( theList[i], theList[j] );
00564                 if ( newEstimate > theDiam->squareDiameter )
00565                 {
00566                     theDiam->extremity1 = theList[i];
00567                     theDiam->extremity2 = theList[j];
00568                     theDiam->squareDiameter = newEstimate;
00569                     if ( newEstimate > upperBound ) upperBound = newEstimate;
00570                 }
00571             }
00572         return( upperBound );
00573     }
00574 
00575 
00576     if ( dim == 3 )
00577     {
00578         for ( i=f;   i<=index; i++ )
00579             for ( j=i+1; j<=l;     j++ )
00580             {
00581                 newEstimate = _SquareDistance3D( theList[i], theList[j] );
00582                 if ( newEstimate > theDiam->squareDiameter )
00583                 {
00584                     theDiam->extremity1 = theList[i];
00585                     theDiam->extremity2 = theList[j];
00586                     theDiam->squareDiameter = newEstimate;
00587                     if ( newEstimate > upperBound ) upperBound = newEstimate;
00588                 }
00589             }
00590         return( upperBound );
00591     }
00592 
00593 
00594     for ( i=f;   i<=index; i++ )
00595         for ( j=i+1; j<=l;     j++ )
00596         {
00597             newEstimate = _SquareDistance( theList[i], theList[j], dim );
00598             if ( newEstimate > theDiam->squareDiameter )
00599             {
00600                 theDiam->extremity1 = theList[i];
00601                 theDiam->extremity2 = theList[j];
00602                 theDiam->squareDiameter = newEstimate;
00603                 if ( newEstimate > upperBound ) upperBound = newEstimate;
00604             }
00605         }
00606     return( upperBound );
00607 }
00608 
00609 }
00610 // ==============================================================
00611 


asr_approx_mvbb
Author(s): Gassner Nikolai
autogenerated on Sat Jun 8 2019 20:21:49