Skip to content

Commit

Permalink
Merge branch 'master' into RimlsPlaneFit
Browse files Browse the repository at this point in the history
  • Loading branch information
AntoineLafon authored Jun 15, 2023
2 parents 548d3ea + 93a0125 commit 087167c
Show file tree
Hide file tree
Showing 17 changed files with 86 additions and 63 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,13 @@ improved doc.

- Bug-fixes and code improvements
- [spatialPartitioning] Fix unwanted function hiding with DryFit::setWeightFunc (#86)
- [fitting] Fix a potential bug when using multi-pass fitting (#89)
- [fitting] Remove deadcode in Basket (#86)
- [ci] Fix Compiler is out of heap space error on Github (MSVC), by splitting tests (#87)

- Tests
- Fix WeightKernel test (failing on windows due to finite differences) (#91)

-Docs
- [spatialPartitioning] Update module page with a minimal doc and examples (#86)
- [spatialPartitioning] Add NanoFlann example (#86)
Expand Down
14 changes: 8 additions & 6 deletions Ponca/src/Fitting/basket.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,13 +41,14 @@ namespace internal
#define WRITE_BASKET_FUNCTIONS \
/*! \brief Convenience function for STL-like iterators */ \
/*! Add neighbors stored in a container using STL-like iterators, and call finalize at the end.*/ \
/*! The fit is evaluated multiple time if needed (see NEED_OTHER_PASS)*/ \
/*! The fit is evaluated multiple time if needed (see #NEED_OTHER_PASS)*/ \
/*! \see addNeighbor() */ \
template <typename IteratorBegin, typename IteratorEnd> \
PONCA_MULTIARCH inline \
FIT_RESULT compute(const IteratorBegin& begin, const IteratorEnd& end){ \
FIT_RESULT res = UNDEFINED; \
do { \
Self::startNewPass(); \
for (auto it = begin; it != end; ++it){ \
Self::addNeighbor(*it); \
} \
Expand All @@ -65,6 +66,7 @@ namespace internal
FIT_RESULT computeWithIds(IndexRange ids, const PointContainer& points){ \
FIT_RESULT res = UNDEFINED; \
do { \
Self::startNewPass(); \
for (const auto& i : ids){ \
this->addNeighbor(points[i]); \
} \
Expand Down Expand Up @@ -145,16 +147,14 @@ namespace internal

WRITE_BASKET_FUNCTIONS

/// Hide Basket::addNeighbor
/// \copydoc Basket::addNeighbor
PONCA_MULTIARCH inline bool addNeighbor(const DataPoint &_nei) {
// compute weight
auto wres = Base::m_w.w(_nei.pos(), _nei);
typename Base::ScalarArray dw;

if (wres.first > Scalar(0.)) {
Base::addLocalNeighbor(wres.first, wres.second, _nei, dw);
Base::m_sumW += (wres.first);
++(Base::m_nbNeighbors);
return true;
}
return false;
Expand Down Expand Up @@ -220,15 +220,17 @@ namespace internal
WRITE_BASKET_FUNCTIONS;

/// \brief Add a neighbor to perform the fit
///
/// When called directly, don't forget to call PrimitiveBase::startNewPass when starting multiple passes
/// \see compute Prefer when using a range of Points
/// \see computeWithIds Prefer when using a range of ids
/// \return false if param nei is not a valid neighbor (weight = 0)
PONCA_MULTIARCH inline bool addNeighbor(const DataPoint &_nei) {
// compute weight
auto wres = Base::m_w.w(_nei.pos(), _nei);

if (wres.first > Scalar(0.)) {
Base::addLocalNeighbor(wres.first, wres.second, _nei);
Base::m_sumW += (wres.first);
++(Base::m_nbNeighbors);
return true;
}
return false;
Expand Down
4 changes: 2 additions & 2 deletions Ponca/src/Fitting/covarianceFit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@ CovarianceFitBase<DataPoint, _WFunctor, T>::finalize ()
{
// handle specific configurations
// With less than 3 neighbors the fitting is undefined
if(Base::finalize() != STABLE || Base::m_nbNeighbors < 3)
if(Base::finalize() != STABLE || Base::getNumNeighbors() < 3)
{
return Base::m_eCurrentState = UNDEFINED;
}

// Center the covariance on the centroid
auto centroid = Base::barycenter();
m_cov = m_cov/Base::m_sumW - centroid * centroid.transpose();
m_cov = m_cov/Base::getWeightSum() - centroid * centroid.transpose();

#ifdef __CUDACC__
m_solver.computeDirect(m_cov);
Expand Down
8 changes: 4 additions & 4 deletions Ponca/src/Fitting/curvatureEstimation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,10 +141,10 @@ NormalCovarianceCurvatureEstimator<DataPoint, _WFunctor, DiffType, T>::finalize
if(this->isReady())
{
// center of gravity (mean)
m_cog /= Base::m_sumW;
m_cog /= Base::getWeightSum();

// Center the covariance on the centroid
m_cov = m_cov/Base::m_sumW - m_cog * m_cog.transpose();
m_cov = m_cov/Base::getWeightSum() - m_cog * m_cog.transpose();

m_solver.computeDirect(m_cov);

Expand Down Expand Up @@ -252,10 +252,10 @@ ProjectedNormalCovarianceCurvatureEstimator<DataPoint, _WFunctor, DiffType, T>::
else if(m_pass == SECOND_PASS)
{
// center of gravity (mean)
m_cog /= Base::m_sumW;
m_cog /= Base::getWeightSum();

// Center the covariance on the centroid
m_cov = m_cov/Base::m_sumW - m_cog * m_cog.transpose();
m_cov = m_cov/Base::getWeightSum() - m_cog * m_cog.transpose();

m_solver.computeDirect(m_cov);

Expand Down
4 changes: 2 additions & 2 deletions Ponca/src/Fitting/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,9 @@ using VectorArray = typename Base::VectorArray; /*!< \brief Alias to vector

// FIT API DOCUMENTATION
#define PONCA_FITTING_APIDOC_SETWFUNC \
/*! Init the WeightFunc, without changing the other internal states. \warning Must be called be for any computation */
/*! Init the WeightFunc, without changing the other internal states. Calls #startNewPass internally. \warning Must be called be for any computation (and before #init). */
#define PONCA_FITTING_APIDOC_INIT \
/*! Set the evaluation position and reset the internal states. \warning Must be called be for any computation */
/*! Set the evaluation position and reset the internal states. \warning Must be called be for any computation (but after #setWeightFunc) */
#define PONCA_FITTING_APIDOC_ADDNEIGHBOR \
/*! Add a neighbor to perform the fit \return false if param nei is not a valid neighbour (weight = 0) */
#define PONCA_FITTING_APIDOC_ADDNEIGHBOR_DER \
Expand Down
4 changes: 2 additions & 2 deletions Ponca/src/Fitting/mean.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace Ponca {
/// Defined as \f$ b(\mathbf{x}) = \frac{\sum_i w_\mathbf{x}(\mathbf{p_i}) \mathbf{p_i}}{\sum_i w_\mathbf{x}(\mathbf{p_i})} \f$,
/// where \f$\left[\mathbf{p_i} \in \text{neighborhood}(\mathbf{x})\right]\f$ are all the point samples in \f$\mathbf{x}\f$'s neighborhood
PONCA_MULTIARCH inline VectorType barycenter() const {
return (m_sumP / Base::m_sumW);
return (m_sumP / Base::getWeightSum());
}

}; //class MeanPosition
Expand Down Expand Up @@ -117,7 +117,7 @@ namespace Ponca {
/// \note This code is not directly tested, but rather indirectly by testing CovariancePlaneDer::dNormal()
PONCA_MULTIARCH VectorArray barycenterDerivatives() const
{
return ( m_dSumP - Base::barycenter() * Base::m_dSumW ) / Base::m_sumW;
return ( m_dSumP - Base::barycenter() * Base::m_dSumW ) / Base::getWeightSum();
}

}; //class MeanPositionDer
Expand Down
2 changes: 1 addition & 1 deletion Ponca/src/Fitting/meanPlaneFit.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ PONCA_FITTING_DECLARE_MATRIX_TYPE
if(Base::finalize() == STABLE)
{
if (Base::plane().isValid()) Base::m_eCurrentState = CONFLICT_ERROR_FOUND;
Base::setPlane(Base::m_sumN / Base::m_sumW, Base::barycenter());
Base::setPlane(Base::m_sumN / Base::getWeightSum(), Base::barycenter());
}
return Base::m_eCurrentState;
}
Expand Down
10 changes: 5 additions & 5 deletions Ponca/src/Fitting/mlsSphereFitDer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,24 +84,24 @@ MlsSphereFitDer<DataPoint, _WFunctor, DiffType, T>::finalize()
sumd2SumPdSumP += m_d2SumP.template block<DerDim,DerDim>(0,i*DerDim)*Base::m_sumP(i);
}

Scalar invSumW = Scalar(1.)/Base::m_sumW;
Scalar invSumW = Scalar(1.)/Base::getWeightSum();

Matrix d2Nume = m_d2SumDotPN
- invSumW*invSumW*invSumW*invSumW*(
Base::m_sumW*Base::m_sumW*( Base::m_sumW*(sumdSumPdSumN+sumdSumPdSumN.transpose()+sumd2SumPdSumN+sumd2SumNdSumP)
Base::getWeightSum()*Base::getWeightSum()*( Base::getWeightSum()*(sumdSumPdSumN+sumdSumPdSumN.transpose()+sumd2SumPdSumN+sumd2SumNdSumP)
+ Base::m_dSumW.transpose()*(Base::m_sumN.transpose()*Base::m_dSumP + Base::m_sumP.transpose()*Base::m_dSumN)
- (Base::m_sumP.transpose()*Base::m_sumN)*m_d2SumW.transpose()
- (Base::m_dSumN.transpose()*Base::m_sumP + Base::m_dSumP.transpose()*Base::m_sumN)*Base::m_dSumW)
- Scalar(2.)*Base::m_sumW*Base::m_dSumW.transpose()*(Base::m_sumW*(Base::m_sumN.transpose()*Base::m_dSumP + Base::m_sumP.transpose()*Base::m_dSumN)
- Scalar(2.)*Base::getWeightSum()*Base::m_dSumW.transpose()*(Base::getWeightSum()*(Base::m_sumN.transpose()*Base::m_dSumP + Base::m_sumP.transpose()*Base::m_dSumN)
- (Base::m_sumP.transpose()*Base::m_sumN)*Base::m_dSumW));

Matrix d2Deno = m_d2SumDotPP
- invSumW*invSumW*invSumW*invSumW*(
Base::m_sumW*Base::m_sumW*( Scalar(2.)*Base::m_sumW*(sumdSumPdSumP+sumd2SumPdSumP)
Base::getWeightSum()*Base::getWeightSum()*( Scalar(2.)*Base::getWeightSum()*(sumdSumPdSumP+sumd2SumPdSumP)
+ Scalar(2.)*Base::m_dSumW.transpose()*(Base::m_sumP.transpose()*Base::m_dSumP)
- (Base::m_sumP.transpose()*Base::m_sumP)*m_d2SumW.transpose()
- Scalar(2.)*(Base::m_dSumP.transpose()*Base::m_sumP)*Base::m_dSumW)
- Scalar(2.)*Base::m_sumW*Base::m_dSumW.transpose()*(Scalar(2.)*Base::m_sumW*Base::m_sumP.transpose()*Base::m_dSumP
- Scalar(2.)*Base::getWeightSum()*Base::m_dSumW.transpose()*(Scalar(2.)*Base::getWeightSum()*Base::m_sumP.transpose()*Base::m_dSumP
- (Base::m_sumP.transpose()*Base::m_sumP)*Base::m_dSumW));

Scalar deno2 = Base::m_deno*Base::m_deno;
Expand Down
12 changes: 6 additions & 6 deletions Ponca/src/Fitting/orientedSphereFit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,17 @@ OrientedSphereFitImpl<DataPoint, _WFunctor, T>::finalize ()
PONCA_MULTIARCH_STD_MATH(abs);

// Compute status
if(Base::finalize() != STABLE || Base::m_nbNeighbors < 3)
if(Base::finalize() != STABLE || Base::getNumNeighbors() < 3)
return Base::m_eCurrentState;
if (Base::algebraicSphere().isValid())
Base::m_eCurrentState = CONFLICT_ERROR_FOUND;
else
Base::m_eCurrentState = Base::m_nbNeighbors < 6 ? UNSTABLE : STABLE;
Base::m_eCurrentState = Base::getNumNeighbors() < 6 ? UNSTABLE : STABLE;

// 1. finalize sphere fitting
Scalar epsilon = Eigen::NumTraits<Scalar>::dummy_precision();

Scalar invSumW = Scalar(1.)/Base::m_sumW;
Scalar invSumW = Scalar(1.)/Base::getWeightSum();

m_nume = (m_sumDotPN - invSumW * Base::m_sumP.dot(Base::m_sumN));
Scalar den1 = invSumW * Base::m_sumP.dot(Base::m_sumP);
Expand Down Expand Up @@ -126,7 +126,7 @@ OrientedSphereDerImpl<DataPoint, _WFunctor, DiffType, T>::finalize()
// Test if base finalize end on a viable case (stable / unstable)
if (this->isReady())
{
Scalar invSumW = Scalar(1.)/Base::m_sumW;
Scalar invSumW = Scalar(1.)/Base::getWeightSum();

Scalar nume = Base::m_sumDotPN - invSumW*Base::m_sumP.dot(Base::m_sumN);
Scalar deno = Base::m_sumDotPP - invSumW*Base::m_sumP.dot(Base::m_sumP);
Expand All @@ -135,11 +135,11 @@ OrientedSphereDerImpl<DataPoint, _WFunctor, DiffType, T>::finalize()
// issues for spacial derivatives because, (d sum w_i P_i)/(d x) is supposed to be tangent to the surface whereas
// "sum w_i N_i" is normal to the surface...
m_dNume = m_dSumDotPN
- invSumW*invSumW * ( Base::m_sumW * ( Base::m_sumN.transpose() * Base::m_dSumP + Base::m_sumP.transpose() * m_dSumN )
- invSumW*invSumW * ( Base::getWeightSum() * ( Base::m_sumN.transpose() * Base::m_dSumP + Base::m_sumP.transpose() * m_dSumN )
- Base::m_dSumW*Base::m_sumP.dot(Base::m_sumN) );

m_dDeno = m_dSumDotPP
- invSumW*invSumW*( Scalar(2.) * Base::m_sumW * Base::m_sumP.transpose() * Base::m_dSumP
- invSumW*invSumW*( Scalar(2.) * Base::getWeightSum() * Base::m_sumP.transpose() * Base::m_dSumP
- Base::m_dSumW*Base::m_sumP.dot(Base::m_sumP) );

m_dUq = Scalar(.5) * (deno * m_dNume - m_dDeno * nume)/(deno*deno);
Expand Down
45 changes: 29 additions & 16 deletions Ponca/src/Fitting/primitive.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,6 @@ namespace Ponca
This class stores and provides public access to the fitting state, and must
be inherited by classes implementing new primitives.
Protected fields #m_eCurrentState and #m_nbNeighbors should be updated
during the fitting process by the inheriting class.
\note This class should not be inherited explicitly: this is done by the
#Basket class.
*/
Expand All @@ -40,34 +37,36 @@ class PrimitiveBase
using VectorType = typename DataPoint::VectorType; /*!< \brief Inherited vector type*/
using WFunctor = _WFunctor; /*!< \brief Weight Function*/

private:
//! \brief Number of neighbors
int m_nbNeighbors {0};

//! \brief Sum of the neighbors weights
Scalar m_sumW {0};

protected:

//! \brief Represent the current state of the fit (finalize function
//! update the state)
FIT_RESULT m_eCurrentState {UNDEFINED};

//! \brief Give the number of neighbors
int m_nbNeighbors {0};

//! \brief Weight function (must inherits BaseWeightFunc)
WFunctor m_w;

//! \brief Sum of the neighbors weights
Scalar m_sumW {0};

public:
/**************************************************************************/
/* Initialization */
/**************************************************************************/
PONCA_FITTING_APIDOC_SETWFUNC
PONCA_MULTIARCH inline void setWeightFunc (const WFunctor& _w) { m_w = _w; }
PONCA_MULTIARCH inline void setWeightFunc (const WFunctor& _w) {
m_w = _w;
}

PONCA_FITTING_APIDOC_INIT
PONCA_MULTIARCH inline void init(const VectorType& _basisCenter = VectorType::Zero())
{
m_eCurrentState = UNDEFINED;
m_nbNeighbors = 0;
m_sumW = Scalar(0);
startNewPass();
m_w.init( _basisCenter );
}

Expand All @@ -79,12 +78,24 @@ class PrimitiveBase
return (m_eCurrentState == STABLE) || (m_eCurrentState == UNSTABLE);
}

/*! \brief Is the plane fitted an ready to use (finalize has been called
and the result is stable, eq. having more than 6 neighbors) */
/*! \brief Is the fitted primitive ready to use (finalize has been called and the result is stable) */
PONCA_MULTIARCH inline bool isStable() const { return m_eCurrentState == STABLE; }

/*! \brief Is another pass required for fitting (finalize has been called and the result is #NEED_OTHER_PASS)
* \see startNewPass */
PONCA_MULTIARCH inline bool needAnotherPass() const { return m_eCurrentState == NEED_OTHER_PASS; }

/*! \brief Get number of points added in the neighborhood (with non negative weight) */
PONCA_MULTIARCH inline int getNumNeighbors() const { return m_nbNeighbors; }
PONCA_MULTIARCH inline int getNumNeighbors() const { return m_nbNeighbors; }

/*! \brief Get the sum of the weights */
PONCA_MULTIARCH inline Scalar getWeightSum() const { return m_sumW; }

/*! \brief To be called when starting a new processing pass, ie. when `getCurrentState()==#NEED_ANOTHER_PASS` */
PONCA_MULTIARCH inline void startNewPass() {
m_nbNeighbors = 0;
m_sumW = Scalar(0);
}

/*! \return the current test of the fit */
PONCA_MULTIARCH inline FIT_RESULT getCurrentState() const
Expand All @@ -93,7 +104,9 @@ class PrimitiveBase
}

PONCA_FITTING_APIDOC_ADDNEIGHBOR
PONCA_MULTIARCH inline bool addLocalNeighbor(Scalar, const VectorType &, const DataPoint &) {
PONCA_MULTIARCH inline bool addLocalNeighbor(Scalar w, const VectorType &, const DataPoint &) {
m_sumW += w;
++(m_nbNeighbors);
return true;
}

Expand Down
4 changes: 2 additions & 2 deletions Ponca/src/Fitting/sphereFit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,12 @@ FIT_RESULT
SphereFitImpl<DataPoint, _WFunctor, T>::finalize ()
{
// Compute status
if(Base::finalize() != STABLE || Base::m_nbNeighbors < 3)
if(Base::finalize() != STABLE || Base::getNumNeighbors() < 3)
return Base::m_eCurrentState = UNDEFINED;
if (Base::algebraicSphere().isValid())
Base::m_eCurrentState = CONFLICT_ERROR_FOUND;
else
Base::m_eCurrentState = Base::m_nbNeighbors < 6 ? UNSTABLE : STABLE;
Base::m_eCurrentState = Base::getNumNeighbors() < 6 ? UNSTABLE : STABLE;

MatrixA matC;
matC.setIdentity();
Expand Down
12 changes: 6 additions & 6 deletions Ponca/src/Fitting/unorientedSphereFit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,15 +90,15 @@ UnorientedSphereFitImpl<DataPoint, _WFunctor, T>::finalize ()
constexpr int Dim = DataPoint::Dim;

// Compute status
if(Base::finalize() != STABLE || Base::m_nbNeighbors < 3)
if(Base::finalize() != STABLE || Base::getNumNeighbors() < 3)
return Base::m_eCurrentState;
if (Base::algebraicSphere().isValid())
Base::m_eCurrentState = CONFLICT_ERROR_FOUND;
else
Base::m_eCurrentState = Base::m_nbNeighbors < 6 ? UNSTABLE : STABLE;
Base::m_eCurrentState = Base::getNumNeighbors() < 6 ? UNSTABLE : STABLE;

// 1. finalize sphere fitting
Scalar invSumW = Scalar(1.) / Base::m_sumW;
Scalar invSumW = Scalar(1.) / Base::getWeightSum();


MatrixBB Q;
Expand Down Expand Up @@ -200,16 +200,16 @@ OrientedSphereDer<DataPoint, _WFunctor, T, Type>::finalize()
if (this->isReady())
{

Scalar invSumW = Scalar(1.)/Base::m_sumW;
Scalar invSumW = Scalar(1.)/Base::getWeightSum();

Scalar nume = Base::m_sumDotPN - invSumW*Base::m_sumP.dot(Base::m_sumN);
Scalar deno = Base::m_sumDotPP - invSumW*Base::m_sumP.dot(Base::m_sumP);

ScalarArray dNume = m_dSumDotPN - invSumW*invSumW * ( Base::m_sumW * (
ScalarArray dNume = m_dSumDotPN - invSumW*invSumW * ( Base::getWeightSum() * (
Base::m_sumN.transpose() * m_dSumP +
Base::m_sumP.transpose() * m_dSumN )
- m_dSumW*Base::m_sumP.dot(Base::m_sumN) );
ScalarArray dDeno = m_dSumDotPP - invSumW*invSumW*( Scalar(2.)*Base::m_sumW * Base::m_sumP.transpose()*m_dSumP
ScalarArray dDeno = m_dSumDotPP - invSumW*invSumW*( Scalar(2.)*Base::getWeightSum() * Base::m_sumP.transpose()*m_dSumP
- m_dSumW*Base::m_sumP.dot(Base::m_sumP) );

m_dUq = Scalar(.5) * (deno * dNume - dDeno * nume)/(deno*deno);
Expand Down
2 changes: 1 addition & 1 deletion Ponca/src/Fitting/weightKernel.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class WendlandWeightKernel


/*!
\brief Singular WeightKernel defined in \f$\left[0 : 1\right]\f$
\brief Singular WeightKernel defined in \f$\left]0 : 1\right]\f$
\inherit Concept::WeightKernelConcept
Expand Down
Loading

0 comments on commit 087167c

Please sign in to comment.