From 2c12e9c6a2c624ef5341b5d86cd1f420f158942f Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Fri, 20 Sep 2024 13:17:51 +0200 Subject: [PATCH] Fix build issues, compiling with Python bindings on --- modules/python/config/rbt.json | 31 +++++++++++ .../include/visp3/rbt/vpColorHistogramMask.h | 1 - .../visp3/rbt/vpRBSilhouetteCCDTracker.h | 2 - .../src/core/vpRBSilhouetteControlPoint.cpp | 54 ++++--------------- .../src/features/vpRBSilhouetteCCDTracker.cpp | 4 -- 5 files changed, 41 insertions(+), 51 deletions(-) create mode 100644 modules/python/config/rbt.json diff --git a/modules/python/config/rbt.json b/modules/python/config/rbt.json new file mode 100644 index 0000000000..eb1680fa79 --- /dev/null +++ b/modules/python/config/rbt.json @@ -0,0 +1,31 @@ +{ + "ignored_headers": [], + "ignored_classes": [], + "user_defined_headers": [], + "classes": { + "vpDynamicFactory": { + "specializations": [ + { + "python_name": "DynamicFactoryTracker", + "arguments": [ + "vpRBFeatureTracker" + ] + }, + { + "python_name": "DynamicFactoryMask", + "arguments": [ + "vpObjectMask" + ] + }, + { + "python_name": "DynamicFactoryDrift", + "arguments": [ + "vpRBDriftDetector" + ] + } + ] + } + }, + "enums": {}, + "config_includes": [] +} diff --git a/modules/tracker/rbt/include/visp3/rbt/vpColorHistogramMask.h b/modules/tracker/rbt/include/visp3/rbt/vpColorHistogramMask.h index 0919c555b1..71e40bd3f3 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpColorHistogramMask.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpColorHistogramMask.h @@ -59,7 +59,6 @@ class VISP_EXPORT vpColorHistogramMask : public vpObjectMask { public: vpColorHistogramMask(); - vpColorHistogramMask(unsigned int N); void updateMask(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, diff --git a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h index 16399a3802..02ca0f189a 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h @@ -273,6 +273,4 @@ class VISP_EXPORT vpRBSilhouetteCCDTracker : public vpRBFeatureTracker }; END_VISP_NAMESPACE - - #endif diff --git a/modules/tracker/rbt/src/core/vpRBSilhouetteControlPoint.cpp b/modules/tracker/rbt/src/core/vpRBSilhouetteControlPoint.cpp index 32002ce403..9fe41b14fb 100644 --- a/modules/tracker/rbt/src/core/vpRBSilhouetteControlPoint.cpp +++ b/modules/tracker/rbt/src/core/vpRBSilhouetteControlPoint.cpp @@ -132,9 +132,6 @@ vpRBSilhouetteControlPoint &vpRBSilhouetteControlPoint::operator=(const vpRBSilh return *this; } - - - int vpRBSilhouetteControlPoint::outOfImage(int i, int j, int half, int rows, int cols) const { return (!((i> half+2) && @@ -174,7 +171,6 @@ void vpRBSilhouetteControlPoint::track(const vpImage &I) } } - void vpRBSilhouetteControlPoint::trackMultipleHypotheses(const vpImage &I) { // If element hasn't been suppressed @@ -190,8 +186,6 @@ void vpRBSilhouetteControlPoint::trackMultipleHypotheses(const vpImageget_px(); @@ -384,48 +367,33 @@ vpRBSilhouetteControlPoint::updateSilhouettePoint(const vpHomogeneousMatrix &cMo } } - void vpRBSilhouetteControlPoint::initControlPoint(const vpImage &I, double cvlt) { double delta = theta; s.init((double)icpoint.get_i(), (double)icpoint.get_j(), delta, cvlt, sign); if (me != nullptr) { const double marginRatio = me->getThresholdMarginRatio(); - double convolution = s.convolution(I, me); + const double convolution = s.convolution(I, me); s.init((double)icpoint.get_i(), (double)icpoint.get_j(), delta, convolution, sign); - double contrastThreshold = fabs(convolution) * marginRatio; + const double contrastThreshold = fabs(convolution) * marginRatio; s.setContrastThreshold(contrastThreshold, *me); } } - void vpRBSilhouetteControlPoint::detectSilhouette(const vpImage &I) { - int k = 0, k1 = 0, k2 = 0; + unsigned int k = 0; int range = 4; double c = cos(theta); double s = sin(theta); for (int n = -range; n <= range; n++) { unsigned int ii = static_cast(round(icpoint.get_i() + s * n)); unsigned int jj = static_cast(round(icpoint.get_j() + c * n)); - int isBg = static_cast(I[ii][jj] == 0.f); + unsigned int isBg = static_cast(I[ii][jj] == 0.f); k += isBg; - k1 += isBg && n < 0; - k2 += isBg && n > 0; - } - if (k > 2) { - isSilhouette = true; - // if (k1 > k2) { - // invnormal = true; - // theta = -theta; - // nxs = -nxs; - // nys = -nys; - // } - // else { - // invnormal = false; - // } } + isSilhouette = k > 2; } /*! @@ -518,13 +486,12 @@ vpRBSilhouetteControlPoint::computeInteractionMatrixErrorMH(const vpHomogeneousM const double yc = cam->get_v0(); const vpMatrix &H = featureline.interaction(); double xmin, ymin; - double errormin = 2.0; + double errormin = std::numeric_limits::max(); - const int n_hyp = m_numCandidates; const std::vector &cs = m_candidates; xmin = (s.m_j - xc) * mx; ymin = (s.m_i - yc) * my; - for (unsigned int l = 0; l < (unsigned)n_hyp; l++) //for each candidate of P + for (unsigned int l = 0; l < m_numCandidates; l++) //for each candidate of P { const vpMeSite &Pk = cs[l]; @@ -557,9 +524,8 @@ vpRBSilhouetteControlPoint::computeInteractionMatrixErrorMH(const vpHomogeneousM bool vpRBSilhouetteControlPoint::isLineDegenerate() const { double a, b, d; - a = line.cP[4]*line.cP[3] - line.cP[0]*line.cP[7]; - b = line.cP[5]*line.cP[3] - line.cP[1]*line.cP[7]; - //c = line.cP[6]*line.cP[3] - line.cP[2]*line.cP[7]; + a = line.cP[4] * line.cP[3] - line.cP[0] * line.cP[7]; + b = line.cP[5] * line.cP[3] - line.cP[1] * line.cP[7]; d = a*a + b*b; return d <= 1e-7; } diff --git a/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp b/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp index 9ad0386f72..dac7de37d6 100644 --- a/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp +++ b/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp @@ -83,10 +83,6 @@ template class FastMat33 } }; - - - - vpRBSilhouetteCCDTracker::vpRBSilhouetteCCDTracker() : vpRBFeatureTracker(), m_vvsConvergenceThreshold(0.0), m_temporalSmoothingFac(0.1) { }