DGtal 2.1.0
Loading...
Searching...
No Matches
QuickHullKernels.h
1
17#pragma once
18
31#if defined(QuickHullKernels_RECURSES)
32#error Recursive header files inclusion detected in QuickHullKernels.h
33#else // defined(QuickHullKernels_RECURSES)
35#define QuickHullKernels_RECURSES
36
37#if !defined QuickHullKernels_h
39#define QuickHullKernels_h
40
42// Inclusions
43#include <iostream>
44#include <string>
45#include <vector>
46#include <array>
47#include "DGtal/base/Common.h"
48#include "DGtal/kernel/CInteger.h"
49#include "DGtal/kernel/NumberTraits.h"
50#include "DGtal/kernel/PointVector.h"
51#include "DGtal/kernel/IntegerConverter.h"
52#include "DGtal/math/linalg/SimpleMatrix.h"
53#include "DGtal/geometry/tools/AffineGeometry.h"
54
55namespace DGtal
56{
57 namespace detail {
58
59 // ------------------------ POINT RELATED SERVICES -----------------------
60
66 template < typename Point >
67 Point center( const std::vector< Point >& points )
68 {
69 if ( points.empty() ) return Point::zero;
70 Point l = points[ 0 ];
71 Point u = l;
72 for ( const auto& p : points ) {
73 l = l.inf( p );
74 u = u.sup( p );
75 }
76 return Point( ( l + u ) / 2 );
77 }
78
107 template < typename OutputValue,
108 typename ForwardIterator,
109 typename ConversionFct >
110 void transform( std::vector< OutputValue >& output_values,
111 std::vector< std::size_t >& input2output,
112 std::vector< std::size_t >& output2input,
113 ForwardIterator itb, ForwardIterator ite,
114 const ConversionFct& F,
115 bool remove_duplicates )
116 {
117 typedef std::size_t Size;
118 // Compute size
119 Size n = 0;
120 for ( auto it = itb; it != ite; ++it ) ++n;
121 std::vector< OutputValue > input( n );
122 for ( Size i = 0; i < n; i++ )
123 input[ i ] = F( *itb++ );
124 if ( ! remove_duplicates ) {
125 output_values.swap( input );
126 input2output.resize( input.size() );
127 output2input.resize( input.size() );
128 for ( Size i = 0; i < input.size(); ++i )
129 input2output[ i ] = output2input[ i ] = i;
130 }
131 else {
132 output_values.clear();
133 std::vector< std::size_t > i2c_sort( input.size() );
134 input2output.resize( input.size() );
135 for ( Size i = 0; i < input.size(); i++ ) i2c_sort[ i ] = i;
136 // indirect sort
137 std::sort( i2c_sort.begin(), i2c_sort.end(),
138 [&input] ( Size i, Size j ) { return input[ i ] < input[ j ]; } );
139 output_values.resize( input.size() );
140 output_values[ 0 ] = input[ i2c_sort[ 0 ] ];
141 input2output[ i2c_sort[ 0 ] ] = 0;
142 Size j = 0;
143 for ( Size i = 1; i < input.size(); i++ ) {
144 if ( input[ i2c_sort[ i-1 ] ] != input[ i2c_sort[ i ] ] )
145 output_values[ ++j ] = input[ i2c_sort[ i ] ];
146 input2output[ i2c_sort[ i ] ] = j;
147 }
148 output_values.resize( j+1 );
149 output2input.resize( output_values.size() );
150 for ( Size i = 0; i < input2output.size(); i++ )
151 output2input[ input2output[ i ] ] = i;
152 }
153 }
154
155 } // namespace detail {
156
157
159 // template class ConvexHullCommonKernel
177 template < Dimension dim,
178 typename TCoordinateInteger = DGtal::int64_t,
179 typename TInternalInteger = DGtal::int64_t >
183 typedef TCoordinateInteger CoordinateInteger;
184 typedef TInternalInteger InternalInteger;
185 //typedef CoordinateInteger Scalar;
188 //typedef DGtal::PointVector< dim, CoordinateInteger > Point;
189 //typedef DGtal::PointVector< dim, CoordinateInteger > Vector;
194 typedef std::size_t Size;
195 typedef Size Index;
196 typedef std::vector< Index > IndexRange;
197 typedef std::array< Index, dim > CombinatorialPlaneSimplex;
198 static const Dimension dimension = dim;
199
201 typedef ConvexHullCommonKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf;
206
207 class HalfSpace {
212 : N( aN ), c( aC ) {}
213 public:
214 HalfSpace() = default;
215 const InternalVector& internalNormal() const { return N; }
217 };
218
221
234 compute( const std::vector< CoordinatePoint >& vpoints,
235 const CombinatorialPlaneSimplex& simplex,
236 Index idx_below )
237 {
238 HalfSpace hs = compute( vpoints, simplex );
239 if ( hs.N != InternalVector::zero )
240 {
241 const InternalPoint ip = Inner::cast( vpoints[ idx_below ] );
242 const InternalScalar nu = hs.N.dot( ip );
243 //const Scalar nu = hs.N.dot( vpoints[ idx_below ] );
244 if ( nu > hs.c ) { hs.N = -hs.N; hs.c = -hs.c; }
245 }
246 return hs;
247 }
248
260 HalfSpace
261 compute( const std::vector< CoordinatePoint >& vpoints,
262 const CombinatorialPlaneSimplex& simplex )
263 {
264 // More robust method than SimpleMatrix::cofactor and faster for higher dimension.
265 InternalVector N; // null normal
266 const InternalPoint ip = Inner::cast( vpoints[ simplex[ 0 ] ] );
267 functions::getOrthogonalVector( N, vpoints, simplex );
268 return HalfSpace { N, N.dot( ip ) };
269 }
270
274 {
275 return Outer::cast( H.N );
276 }
277
281 {
282 return Outer::cast( H.c );
283 }
284
293 InternalScalar dot( const HalfSpace& H1, const HalfSpace& H2 ) const
294 {
295 return H1.N.dot( H2.N );
296 }
297
306 bool equal( const HalfSpace& H1, const HalfSpace& H2 ) const
307 {
308 return H1.c == H2.c && H1.N == H2.N;
309 }
310
315 { return H.N.dot( Inner::cast( p ) ) - H.c; }
316
321 {
322 InternalScalar v = height( H, p );
323 return v < InternalScalar( 0 ) ? -v : v;
324 }
325
329 bool above( const HalfSpace& H, const CoordinatePoint& p ) const
330 { return height( H, p ) > 0; }
331
335 bool aboveOrOn( const HalfSpace& H, const CoordinatePoint& p ) const
336 { return height( H, p ) >= 0; }
337
341 bool on( const HalfSpace& H, const CoordinatePoint& p ) const
342 { return height( H, p ) == 0; }
343
344
345 }; // template < Dimension dim > struct ConvexHullIntegralKernel {
346
347
348
350 // template class ConvexHullIntegralKernel
368 template < Dimension dim,
369 typename TCoordinateInteger = DGtal::int64_t,
370 typename TInternalInteger = DGtal::int64_t >
372 : public ConvexHullCommonKernel< dim, TCoordinateInteger, TInternalInteger >
373 {
376 typedef ConvexHullIntegralKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf;
377 // inheriting types
378 using typename Base::CoordinatePoint;
381 using typename Base::InternalPoint;
382 using typename Base::InternalVector;
383 using typename Base::InternalScalar;
384 using typename Base::Size;
385 using typename Base::Index;
386 using typename Base::IndexRange;
388 using typename Base::HalfSpace;
389 // inheriting constants
391 // inheriting methods
401 using Base::on;
402
405
409 bool hasInfiniteFacets() const
410 { return false; }
411
416 bool isHalfSpaceFacetInfinite( const HalfSpace& hs ) const
417 {
418 (void) hs; // unused parameter
419 return false;
420 }
421
447 template < typename InputPoint>
448 void makeInput( std::vector< CoordinatePoint >& processed_points,
449 IndexRange& input2comp, IndexRange& comp2input,
450 const std::vector< InputPoint >& input_points,
451 bool remove_duplicates )
452 {
453 const auto F = [&] ( InputPoint input ) -> CoordinatePoint
454 {
456 for ( Dimension i = 0; i < dimension; i++ )
457 p[ i ] = CoordinateScalar( input[ i ] );
458 return p;
459 };
460 DGtal::detail::transform( processed_points, input2comp, comp2input,
461 input_points.cbegin(), input_points.cend(),
462 F, remove_duplicates );
463 }
464
467 template < typename OutputPoint>
468 void convertPointTo( const CoordinatePoint& p, OutputPoint& out_p ) const
469 {
470 for ( Dimension k = 0; k < dimension; k++ )
471 out_p[ k ] = static_cast<typename OutputPoint::Component>(p[ k ]);
472 }
473
474 }; // template < Dimension dim > struct ConvexHullIntegralKernel {
475
476
478 // template class DelaunayIntegralKernel
499 template < Dimension dim,
500 typename TCoordinateInteger = DGtal::int64_t,
501 typename TInternalInteger = DGtal::int64_t >
503 : public ConvexHullCommonKernel< dim+1, TCoordinateInteger, TInternalInteger >
504 {
507 typedef DelaunayIntegralKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf;
508 // inheriting types
509 // using typename Base::Point;
510 // using typename Base::Vector;
511 // using typename Base::Scalar;
512 using typename Base::CoordinatePoint;
513 using typename Base::CoordinateVector;
514 using typename Base::CoordinateScalar;
515 using typename Base::InternalPoint;
516 using typename Base::InternalVector;
517 using typename Base::InternalScalar;
518 using typename Base::Size;
519 using typename Base::Index;
520 using typename Base::IndexRange;
521 using typename Base::CombinatorialPlaneSimplex;
522 using typename Base::HalfSpace;
523 // inheriting constants
524 using Base::dimension;
525 // inheriting methods
526 using Base::compute;
527 using Base::normal;
528 using Base::intercept;
529 using Base::dot;
530 using Base::equal;
531 using Base::height;
532 using Base::volume;
533 using Base::above;
534 using Base::aboveOrOn;
535 using Base::on;
536
539
543 bool hasInfiniteFacets() const
544 { return true; }
545
550 bool isHalfSpaceFacetInfinite( const HalfSpace& hs ) const
551 {
552 return hs.internalNormal()[ dimension - 1 ] >= InternalScalar( 0 );
553 }
554
584 template < typename InputPoint>
585 void makeInput( std::vector< CoordinatePoint >& processed_points,
586 IndexRange& input2comp, IndexRange& comp2input,
587 const std::vector< InputPoint >& input_points,
588 bool remove_duplicates )
589 {
590 const auto F = [&] ( InputPoint input ) -> CoordinatePoint
591 {
593 CoordinateScalar z = 0;
594 for ( Dimension i = 0; i < dimension-1; i++ ) {
595 const CoordinateScalar x = CoordinateScalar( input[ i ] );
596 p[ i ] = x;
597 z += x*x;
598 }
599 p[ dimension-1 ] = z;
600 return p;
601 };
602 DGtal::detail::transform( processed_points, input2comp, comp2input,
603 input_points.cbegin(), input_points.cend(),
604 F, remove_duplicates );
605 }
606
609 template < typename OutputPoint>
610 void convertPointTo( const CoordinatePoint& p, OutputPoint& out_p ) const
611 {
612 for ( Dimension k = 0; k < dimension-1; k++ )
613 out_p[ k ] = p[ k ];
614 }
615
616 }; // template < Dimension dim > struct DelaunayIntegralKernel {
617
618
620 // template class ConvexHullRationalKernel
651 template < Dimension dim,
652 typename TCoordinateInteger = DGtal::int64_t,
653 typename TInternalInteger = DGtal::int64_t >
655 : public ConvexHullCommonKernel< dim, TCoordinateInteger, TInternalInteger >
656 {
659 typedef ConvexHullRationalKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf;
660 // inheriting types
661 // using typename Base::Point;
662 // using typename Base::Vector;
663 // using typename Base::Scalar;
664 using typename Base::CoordinatePoint;
665 using typename Base::CoordinateVector;
666 using typename Base::CoordinateScalar;
667 using typename Base::InternalPoint;
668 using typename Base::InternalVector;
669 using typename Base::InternalScalar;
670 using typename Base::Size;
671 using typename Base::Index;
672 using typename Base::IndexRange;
673 using typename Base::CombinatorialPlaneSimplex;
674 using typename Base::HalfSpace;
675 // inheriting constants
676 using Base::dimension;
677 // inheriting methods
678 using Base::compute;
679 using Base::normal;
680 using Base::intercept;
681 using Base::dot;
682 using Base::equal;
683 using Base::height;
684 using Base::volume;
685 using Base::above;
686 using Base::aboveOrOn;
687 using Base::on;
688
690 double precision;
691
696 ConvexHullRationalKernel( double aPrecision = 1024. )
697 : precision( aPrecision ) {}
698
702 bool hasInfiniteFacets() const
703 { return false; }
704
709 bool isHalfSpaceFacetInfinite( const HalfSpace& hs ) const
710 {
711 (void) hs; // unused parameter
712 return false;
713 }
714
745 template < typename InputPoint>
746 void makeInput( std::vector< CoordinatePoint >& processed_points,
747 IndexRange& input2comp, IndexRange& comp2input,
748 const std::vector< InputPoint >& input_points,
749 bool remove_duplicates )
750 {
751 const auto F = [&] ( InputPoint input ) -> CoordinatePoint
752 {
754 for ( Dimension i = 0; i < dimension; i++ )
755 p[ i ] = CoordinateScalar( round( input[ i ] * precision ) );
756 return p;
757 };
758 DGtal::detail::transform( processed_points, input2comp, comp2input,
759 input_points.cbegin(), input_points.cend(),
760 F, remove_duplicates );
761 }
762
779 template < typename OutputPoint>
780 void convertPointTo( const CoordinatePoint& p, OutputPoint& out_p ) const
781 {
782 for ( Dimension k = 0; k < dimension; k++ )
783 out_p[ k ] = ( (double) p[ k ] ) / precision;
784 }
785
786
787 }; // template < Dimension dim > struct ConvexHullRationalKernel {
788
789
791 // template class DelaunayRationalKernel
825 template < Dimension dim,
826 typename TCoordinateInteger = DGtal::int64_t,
827 typename TInternalInteger = DGtal::int64_t >
829 : public ConvexHullCommonKernel< dim+1, TCoordinateInteger, TInternalInteger >
830 {
833 typedef DelaunayRationalKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf;
834 // inheriting types
835 // using typename Base::Point;
836 // using typename Base::Vector;
837 // using typename Base::Scalar;
838 using typename Base::CoordinatePoint;
839 using typename Base::CoordinateVector;
840 using typename Base::CoordinateScalar;
841 using typename Base::InternalPoint;
842 using typename Base::InternalVector;
843 using typename Base::InternalScalar;
844 using typename Base::Size;
845 using typename Base::Index;
846 using typename Base::IndexRange;
847 using typename Base::CombinatorialPlaneSimplex;
848 using typename Base::HalfSpace;
849 // inheriting constants
850 using Base::dimension;
851 // inheriting methods
852 using Base::compute;
853 using Base::normal;
854 using Base::intercept;
855 using Base::dot;
856 using Base::equal;
857 using Base::height;
858 using Base::volume;
859 using Base::above;
860 using Base::aboveOrOn;
861 using Base::on;
862
864 double precision;
865
870 DelaunayRationalKernel( double aPrecision = 1024. )
871 : precision( aPrecision ) {}
872
876 bool hasInfiniteFacets() const
877 { return true; }
878
883 bool isHalfSpaceFacetInfinite( const HalfSpace& hs ) const
884 {
885 return hs.internalNormal()[ dimension - 1 ] >= InternalScalar( 0 );
886 }
887
923 template < typename InputPoint>
924 void makeInput( std::vector< CoordinatePoint >& processed_points,
925 IndexRange& input2comp, IndexRange& comp2input,
926 const std::vector< InputPoint >& input_points,
927 bool remove_duplicates )
928 {
929 const auto F = [&] ( InputPoint input ) -> CoordinatePoint
930 {
932 CoordinateScalar z = 0;
933 for ( Dimension i = 0; i < dimension - 1; i++ ) {
934 const CoordinateScalar x
935 = CoordinateScalar( round( input[ i ] * precision ) );
936 p[ i ] = x;
937 z += x*x;
938 }
939 p[ dimension-1 ] = z;
940 return p;
941 };
942 DGtal::detail::transform( processed_points, input2comp, comp2input,
943 input_points.cbegin(), input_points.cend(),
944 F, remove_duplicates );
945 }
946
966 template < typename OutputPoint>
967 void convertPointTo( const CoordinatePoint& p, OutputPoint& out_p ) const
968 {
969 for ( Dimension k = 0; k < dimension - 1; k++ )
970 out_p[ k ] = ( (double) p[ k ] ) / precision;
971 }
972
973 }; // template < Dimension dim > struct DelaunayRationalKernel {
974
975
976
977} // namespace DGtal {
978
979#endif // !defined QuickHullKernels_h
980
981#undef QuickHullKernels_RECURSES
982#endif // else defined(QuickHullKernels_RECURSES)
HalfSpace(const InternalVector &aN, const InternalScalar aC)
InternalVector N
the normal vector
const InternalVector & internalNormal() const
Aim: Implements basic operations that will be used in Point and Vector classes.
auto dot(const PointVector< dim, OtherComponent, OtherStorage > &v) const -> decltype(DGtal::dotProduct(*this, v))
Dot product with a PointVector.
static Self zero
Static const for zero PointVector.
void transform(std::vector< OutputValue > &output_values, std::vector< std::size_t > &input2output, std::vector< std::size_t > &output2input, ForwardIterator itb, ForwardIterator ite, const ConversionFct &F, bool remove_duplicates)
Point center(const std::vector< Point > &points)
static void getOrthogonalVector(TPoint &w, const std::vector< TInputPoint > &X, const TIndexRange &I, const double tolerance=1e-12)
DGtal is the top-level namespace which contains all DGtal functions and types.
std::int64_t int64_t
signed 94-bit integer.
Definition BasicTypes.h:73
DGtal::uint32_t Dimension
Definition Common.h:119
Aim: the common part of all geometric kernels for computing the convex hull or Delaunay triangulation...
DGtal::PointVector< dim, InternalInteger > InternalVector
BOOST_CONCEPT_ASSERT((concepts::CInteger< TCoordinateInteger >))
std::array< Index, dim > CombinatorialPlaneSimplex
bool above(const HalfSpace &H, const CoordinatePoint &p) const
InternalScalar height(const HalfSpace &H, const CoordinatePoint &p) const
HalfSpace compute(const std::vector< CoordinatePoint > &vpoints, const CombinatorialPlaneSimplex &simplex)
TCoordinateInteger CoordinateInteger
CoordinateVector normal(const HalfSpace &H) const
InternalScalar volume(const HalfSpace &H, const CoordinatePoint &p) const
InternalScalar dot(const HalfSpace &H1, const HalfSpace &H2) const
HalfSpace compute(const std::vector< CoordinatePoint > &vpoints, const CombinatorialPlaneSimplex &simplex, Index idx_below)
DGtal::PointVector< dim, CoordinateInteger > CoordinatePoint
std::vector< Index > IndexRange
bool equal(const HalfSpace &H1, const HalfSpace &H2) const
BOOST_CONCEPT_ASSERT((concepts::CInteger< TInternalInteger >))
DGtal::PointVector< dim, InternalInteger > InternalPoint
IntegerConverter< dim, InternalInteger > Inner
Converter to inner internal integers or lattice points / vector.
bool on(const HalfSpace &H, const CoordinatePoint &p) const
static const Dimension dimension
ConvexHullCommonKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf
bool aboveOrOn(const HalfSpace &H, const CoordinatePoint &p) const
IntegerConverter< dim, CoordinateInteger > Outer
Converter to outer coordinate integers or lattice points / vector.
ConvexHullCommonKernel< dim, TCoordinateInteger, TInternalInteger > Self
ConvexHullCommonKernel()=default
Default constructor.
CoordinateScalar intercept(const HalfSpace &H) const
DGtal::PointVector< dim, CoordinateInteger > CoordinateVector
Aim: a geometric kernel to compute the convex hull of digital points with integer-only arithmetic.
ConvexHullCommonKernel< dim, TCoordinateInteger, TInternalInteger > Base
void convertPointTo(const CoordinatePoint &p, OutputPoint &out_p) const
ConvexHullIntegralKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf
void makeInput(std::vector< CoordinatePoint > &processed_points, IndexRange &input2comp, IndexRange &comp2input, const std::vector< InputPoint > &input_points, bool remove_duplicates)
bool isHalfSpaceFacetInfinite(const HalfSpace &hs) const
static const Dimension dimension
ConvexHullIntegralKernel()=default
Default constructor.
ConvexHullIntegralKernel< dim, TCoordinateInteger, TInternalInteger > Self
Aim: a geometric kernel to compute the convex hull of floating points with integer-only arithmetic....
void convertPointTo(const CoordinatePoint &p, OutputPoint &out_p) const
void makeInput(std::vector< CoordinatePoint > &processed_points, IndexRange &input2comp, IndexRange &comp2input, const std::vector< InputPoint > &input_points, bool remove_duplicates)
double precision
The precision as the common denominator for all rational points.
bool isHalfSpaceFacetInfinite(const HalfSpace &hs) const
ConvexHullRationalKernel(double aPrecision=1024.)
static const Dimension dimension
ConvexHullCommonKernel< dim, TCoordinateInteger, TInternalInteger > Base
ConvexHullRationalKernel< dim, TCoordinateInteger, TInternalInteger > Self
ConvexHullRationalKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf
Aim: a geometric kernel to compute the Delaunay triangulation of digital points with integer-only ari...
std::vector< Index > IndexRange
ConvexHullCommonKernel< dim+1, TCoordinateInteger, TInternalInteger > Base
void convertPointTo(const CoordinatePoint &p, OutputPoint &out_p) const
DelaunayIntegralKernel< dim, TCoordinateInteger, TInternalInteger > Self
DelaunayIntegralKernel()=default
Default constructor.
void makeInput(std::vector< CoordinatePoint > &processed_points, IndexRange &input2comp, IndexRange &comp2input, const std::vector< InputPoint > &input_points, bool remove_duplicates)
static const Dimension dimension
bool isHalfSpaceFacetInfinite(const HalfSpace &hs) const
DelaunayIntegralKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf
Aim: a geometric kernel to compute the Delaunay triangulation of a range of floating points with inte...
DelaunayRationalKernel< dim, TCoordinateInteger, TInternalInteger > Self
std::vector< Index > IndexRange
double precision
The precision as the common denominator for all rational points.
ConvexHullCommonKernel< dim+1, TCoordinateInteger, TInternalInteger > Base
DelaunayRationalKernel(double aPrecision=1024.)
static const Dimension dimension
void makeInput(std::vector< CoordinatePoint > &processed_points, IndexRange &input2comp, IndexRange &comp2input, const std::vector< InputPoint > &input_points, bool remove_duplicates)
void convertPointTo(const CoordinatePoint &p, OutputPoint &out_p) const
DelaunayRationalKernel< dim-1, TCoordinateInteger, TInternalInteger > LowerSelf
bool isHalfSpaceFacetInfinite(const HalfSpace &hs) const
----------— INTEGER/POINT CONVERSION SERVICES -----------------—
static Integer cast(Integer i)
Aim: Concept checking for Integer Numbers. More precisely, this concept is a refinement of both CEucl...
Definition CInteger.h:88
MyPointD Point
HalfEdgeDataStructure::Size Size