Skip to content

Commit

Permalink
Fix most warnings from the initial commit
Browse files Browse the repository at this point in the history
  • Loading branch information
SamFlt committed Sep 19, 2024
1 parent dd16fdc commit 25635f9
Show file tree
Hide file tree
Showing 18 changed files with 205 additions and 251 deletions.
2 changes: 1 addition & 1 deletion modules/tracker/rbt/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ if(WITH_SIMDLIB)
list(APPEND opt_libs_private ${SIMDLIB_LIBRARIES})
endif()

vp_add_module(rbt visp_mbt visp_vision visp_core visp_me visp_visual_features visp_ar OPTIONAL visp_klt visp_gui PRIVATE_OPTIONAL ${opt_libs_private})
vp_add_module(rbt visp_vision visp_core visp_me visp_visual_features visp_ar OPTIONAL visp_klt visp_gui PRIVATE_OPTIONAL ${opt_libs_private})
vp_glob_module_sources()

vp_module_include_directories(${opt_incs})
Expand Down
14 changes: 2 additions & 12 deletions modules/tracker/rbt/include/visp3/rbt/vpRBDenseDepthTracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,24 +39,16 @@
#define VP_RB_DENSE_DEPTH_TRACKER_H

#include <visp3/core/vpConfig.h>
#include <visp3/core/vpMatrix.h>
#include <visp3/core/vpColVector.h>
#include <visp3/core/vpMatrixException.h>
#include <visp3/core/vpImage.h>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/vision/vpPose.h>
#include <visp3/core/vpExponentialMap.h>
#include <visp3/core/vpPixelMeterConversion.h>
#include <visp3/core/vpRobust.h>
#include <visp3/core/vpMatrixException.h>
#include <visp3/core/vpMatrix.h>
#include <visp3/core/vpPoint.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/visual_features/vpFeatureDepth.h>

// #if defined(VISP_HAVE_SIMDLIB)
// #include <Simd/SimdLib.h>
// #endif
#include <visp3/rbt/vpRBSilhouetteControlPoint.h>
#include <visp3/rbt/vpRBFeatureTracker.h>

#include <vector>
Expand Down Expand Up @@ -116,9 +108,7 @@ class VISP_EXPORT vpRBDenseDepthTracker : public vpRBFeatureTracker

inline void error(vpColVector &e, unsigned i) const
{

double D = -((cameraNormal[0] * oP.get_X()) + (cameraNormal[1] * oP.get_Y()) + (cameraNormal[2] * oP.get_Z()));

double projNormal = cameraNormal[0] * currentPoint[0] + cameraNormal[1] * currentPoint[1] + cameraNormal[2] * currentPoint[2];

e[i] = D + projNormal;
Expand Down
1 change: 0 additions & 1 deletion modules/tracker/rbt/include/visp3/rbt/vpRBFeatureTracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpRect.h>


#include <visp3/rbt/vpRBFeatureTrackerInput.h>
#include <visp3/rbt/vpRBSilhouettePoint.h>

Expand Down
11 changes: 1 addition & 10 deletions modules/tracker/rbt/include/visp3/rbt/vpRBKltTracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker
public:
vpRBKltTracker();


bool requiresRGB() const VP_OVERRIDE { return false; }

bool requiresDepth() const VP_OVERRIDE { return false; }
Expand All @@ -68,7 +67,6 @@ class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker

void onTrackingIterEnd() VP_OVERRIDE { }


void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;

void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
Expand Down Expand Up @@ -112,9 +110,9 @@ class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker
inline double rotationDifferenceToInitial(const vpHomogeneousMatrix &oMc)
{
const vpHomogeneousMatrix cinitTc = cTo0 * oMc;

return cinitTc.getThetaUVector().getTheta();
}

inline double normalDotProd(const vpHomogeneousMatrix &cMo)
{
vpColVector cameraNormal = cMo.getRotationMatrix() * normal;
Expand All @@ -136,12 +134,6 @@ class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker
e[i * 2 + 1] = oX.get_y() - currentPos.get_v();
}

inline double weight(const vpHomogeneousMatrix &cMo)
{
//return static_cast<double>(validAndInlierCount) / static_cast<double>(validCount);
return 1.0;
}

inline double distance(const vpTrackedKltPoint &other) const
{
const double d = sqrt(std::pow(oX.get_oX() - other.oX.get_oX(), 2) +
Expand All @@ -150,7 +142,6 @@ class VISP_EXPORT vpRBKltTracker : public vpRBFeatureTracker
return d;
}


inline void interaction(vpMatrix &L, unsigned i) const
{
double x = oX.get_x(), y = oX.get_y();
Expand Down
15 changes: 4 additions & 11 deletions modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,6 @@ class VISP_EXPORT vpCCDParameters
* maximum decrease of the covariance within one iteration step. Between 0 and 1
* If c2 is too high, the covariance declines slowly. Hence, a small number of iterations is
* necessary. If c2 is too small, the CCD algorithm may converge to a wrong solution.
*
* it is recommended to leave this value fixed
*/
double covarianceIterDecreaseFactor;
Expand All @@ -115,14 +114,12 @@ class VISP_EXPORT vpCCDParameters
* Length of the line along the normal (and the opposite direction). To subsample the line, set delta_h > 1.
* Number of pixels used is computed as 2 * floor(h/delta_h). If you expect large motions, set a large value.
* If you want to reduce computation time, decrease this value or increase delta_h
* Recommended value: above 4
*
* Recommended value: 4 or above (this is dependent on image resolution)
*/
int h;
/**
* \brief Sample step when computing statistics and errors.
* Increase this value to decrease computation time, at the risk of obtaining inacurrate statistics.
*
*/
int delta_h;
/**
Expand All @@ -145,7 +142,7 @@ inline void from_json(const nlohmann::json &j, vpCCDParameters &ccdParameters)
ccdParameters.phi_dim = j.value("phi_dim", ccdParameters.phi_dim);
if (j.contains("gamma")) {
nlohmann::json gammaj = j["gamma"];
if (!j.is_array() || !j.size() != 4) {
if (!j.is_array() || j.size() != 4) {
throw vpException(vpException::ioError, "CCD parameters: tried to read gamma values from something that is not a 4-sized float array");
}
ccdParameters.gamma_1 = gammaj[0];
Expand Down Expand Up @@ -179,10 +176,6 @@ class VISP_EXPORT vpCCDStatistics
};


/**
* \brief A base class for all features that can be used and tracker in the vpRenderBasedTracker
*
*/
class VISP_EXPORT vpRBSilhouetteCCDTracker : public vpRBFeatureTracker
{
public:
Expand Down Expand Up @@ -224,11 +217,11 @@ class VISP_EXPORT vpRBSilhouetteCCDTracker : public vpRBFeatureTracker
double getVVSTrackerWeight() const VP_OVERRIDE { return m_userVvsWeight / (10 * error_ccd.size()); }

void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE { }
void trackFeatures(const vpRBFeatureTrackerInput & /*frame*/, const vpRBFeatureTrackerInput & /*previousFrame*/, const vpHomogeneousMatrix & /*cMo*/) VP_OVERRIDE { }

void initVVS(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
void computeVVSIter(const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cMo, unsigned int iteration) VP_OVERRIDE;
void updateCovariance(const double lambda) VP_OVERRIDE { }
void updateCovariance(const double /*lambda*/) VP_OVERRIDE { }

void display(const vpCameraParameters &cam, const vpImage<unsigned char> &I, const vpImage<vpRGBa> &IRGB, const vpImage<unsigned char> &depth, const vpRBFeatureDisplayType type) const VP_OVERRIDE;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,8 +166,8 @@ class VISP_EXPORT vpRBSilhouetteControlPoint
void trackMultipleHypotheses(const vpImage<unsigned char> &I);

void initInteractionMatrixError();
void computeInteractionMatrixError(const vpHomogeneousMatrix &cMo, const vpImage<unsigned char> &I);
void computeInteractionMatrixErrorMH(const vpHomogeneousMatrix &cMo, const vpImage<unsigned char> &I);
void computeInteractionMatrixError(const vpHomogeneousMatrix &cMo);
void computeInteractionMatrixErrorMH(const vpHomogeneousMatrix &cMo);

private:
void sample(const vpImage<unsigned char> &) { }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,13 @@

#include <visp3/rbt/vpRBFeatureTracker.h>
#include <visp3/rbt/vpRBSilhouetteControlPoint.h>
#include <visp3/core/vpTrackingException.h>
#include <visp3/core/vpRobust.h>

class VISP_EXPORT vpRBSilhouetteMeTracker : public vpRBFeatureTracker
{
public:

vpRBSilhouetteMeTracker() : vpRBFeatureTracker(), m_me(), m_numCandidates(1), m_globalVVSConvergenceThreshold(1.0), m_singlePointConvergedThresholdPixels(3), m_minMaskConfidence(0.f), m_useMask(false) { }
vpRBSilhouetteMeTracker() : vpRBFeatureTracker(), m_me(), m_numCandidates(1), m_globalVVSConvergenceThreshold(1.0), m_singlePointConvergedThresholdPixels(3), m_useMask(false), m_minMaskConfidence(0.f) { }

bool requiresRGB() const VP_OVERRIDE { return false; }

Expand All @@ -68,8 +67,6 @@ class VISP_EXPORT vpRBSilhouetteMeTracker : public vpRBFeatureTracker
*/
void extractFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;

void clusterIntoLines();

void trackFeatures(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;

void initVVS(const vpRBFeatureTrackerInput &frame, const vpRBFeatureTrackerInput &previousFrame, const vpHomogeneousMatrix &cMo) VP_OVERRIDE;
Expand Down Expand Up @@ -98,9 +95,9 @@ class VISP_EXPORT vpRBSilhouetteMeTracker : public vpRBFeatureTracker
std::vector<vpRBSilhouetteControlPoint> m_controlPoints;
vpMe m_me; //! Moving edge settings
unsigned int m_numCandidates; //! Number of best candidates kept when finding correspondence points
double m_singlePointConvergedThresholdPixels; //! Whether a single Control point is considered as converged
double m_globalVVSConvergenceThreshold; //! Percentage of control points that should have converged to consider VVS as successful
vpRobust m_robust; //! M-Estimator to filter outliers
double m_globalVVSConvergenceThreshold; //! Percentage of control points that should have converged to consider VVS as successful
double m_singlePointConvergedThresholdPixels; //! Whether a single Control point is considered as converged
bool m_useMask;
float m_minMaskConfidence;

Expand Down
2 changes: 1 addition & 1 deletion modules/tracker/rbt/include/visp3/rbt/vpRBTrackerLogger.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ std::ostream &operator<<(std::ostream &out, const vpRBTrackerLogger &timer)
out << "Silhouette extraction: " << timer.m_silhouetteExtractionTime << "ms" << std::endl;

out << "Trackers: " << std::endl;
for (const std::pair<const int, std::vector<double>> vvsIterData : timer.m_trackerVVSIterTimes) {
for (const std::pair<const int, std::vector<double>> &vvsIterData : timer.m_trackerVVSIterTimes) {
double featTrackTime = timer.m_trackerFeatureTrackingTime.find(vvsIterData.first)->second;
double featExtractionTime = timer.m_trackerFeatureExtractionTime.find(vvsIterData.first)->second;
double initVVSTime = timer.m_trackerInitVVSTime.find(vvsIterData.first)->second;
Expand Down
18 changes: 7 additions & 11 deletions modules/tracker/rbt/src/core/vpRBSilhouetteControlPoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,8 +165,8 @@ void vpRBSilhouetteControlPoint::track(const vpImage<unsigned char> &I)
s.track(I, me, false);
}
}
catch (vpTrackingException) {
vpERROR_TRACE("catch exception ");
catch (vpTrackingException &) {
vpERROR_TRACE("caught a tracking exception, ignoring me point...");
s.setState(vpMeSite::THRESHOLD);
}
}
Expand All @@ -178,12 +178,12 @@ void vpRBSilhouetteControlPoint::trackMultipleHypotheses(const vpImage<unsigned
// If element hasn't been suppressed
try {
if (s.getState() == vpMeSite::NO_SUPPRESSION) {
const bool testContrast = s.m_convlt != 0.0;
//const bool testContrast = s.m_convlt != 0.0;
s.trackMultipleHypotheses(I, *me, false, m_candidates, m_numCandidates);
}
}
catch (vpTrackingException) {
vpERROR_TRACE("catch exception ");
catch (vpTrackingException &) {
vpERROR_TRACE("caught a tracking exception, ignoring me point...");
s.setState(vpMeSite::THRESHOLD);
}
}
Expand Down Expand Up @@ -364,7 +364,6 @@ vpRBSilhouetteControlPoint::updateSilhouettePoint(const vpHomogeneousMatrix &cMo
m_valid = !isLineDegenerate();
if (m_valid) {
vpFeatureBuilder::create(featureline, line);
double theta0 = theta;
theta = featureline.getTheta();
#if VISP_DEBUG_RB_CONTROL_POINT
if (std::isnan(theta)) {
Expand Down Expand Up @@ -441,14 +440,11 @@ vpRBSilhouetteControlPoint::initInteractionMatrixError()
error = 0;
}




/*!
Compute the interaction matrix and the error vector corresponding to the line.
*/
void
vpRBSilhouetteControlPoint::computeInteractionMatrixError(const vpHomogeneousMatrix &cMo, const vpImage<unsigned char> &/*I*/)
vpRBSilhouetteControlPoint::computeInteractionMatrixError(const vpHomogeneousMatrix &cMo)
{
line.changeFrame(cMo);

Expand Down Expand Up @@ -496,7 +492,7 @@ vpRBSilhouetteControlPoint::computeInteractionMatrixError(const vpHomogeneousMat
}

void
vpRBSilhouetteControlPoint::computeInteractionMatrixErrorMH(const vpHomogeneousMatrix &cMo, const vpImage<unsigned char> &/*I*/)
vpRBSilhouetteControlPoint::computeInteractionMatrixErrorMH(const vpHomogeneousMatrix &cMo)
{
line.changeFrame(cMo);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ std::vector<std::pair<unsigned int, unsigned int>> vpSilhouettePointsExtractionS
}
if (m_preferPreviousPoints) {
for (const vpRBSilhouettePoint &p: previousPoints) {
double x, y;
double x = 0.0, y = 0.0;
vpPixelMeterConversion::convertPoint(cam, p.j, p.i, x, y);
vpColVector cpX({ x * p.Z, y * p.Z, p.Z, 1.0 });
vpColVector cX = cTcp * cpX;
Expand All @@ -100,7 +100,7 @@ std::vector<std::pair<unsigned int, unsigned int>> vpSilhouettePointsExtractionS
}
}
}
if (m_maxNumPoints > 0 && finalCandidates.size() >= m_maxNumPoints) {
if (m_maxNumPoints > 0 && finalCandidates.size() >= static_cast<unsigned int>(m_maxNumPoints)) {
return finalCandidates;
}

Expand Down
4 changes: 1 addition & 3 deletions modules/tracker/rbt/src/core/vpRBTracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,7 @@
#define VP_DEBUG_RB_TRACKER 1


vpRBTracker::vpRBTracker() : m_lambda(1.0), m_vvsIterations(10), m_muInit(0.0), m_muIterFactor(0.5), m_imageHeight(480), m_imageWidth(640),
m_firstIteration(true), m_renderer(m_rendererSettings), m_trackers(0)
vpRBTracker::vpRBTracker() : m_firstIteration(true), m_trackers(0), m_lambda(1.0), m_vvsIterations(10), m_muInit(0.0), m_muIterFactor(0.5), m_renderer(m_rendererSettings), m_imageHeight(480), m_imageWidth(640)
{
m_rendererSettings.setClippingDistance(0.01, 1.0);
const std::shared_ptr<vpPanda3DGeometryRenderer> geometryRenderer = std::make_shared<vpPanda3DGeometryRenderer>(
Expand Down Expand Up @@ -283,7 +282,6 @@ void vpRBTracker::track(vpRBFeatureTrackerInput &input)
error += (weight * tracker->getWeightedError()).sumSquare();
//std::cout << "Error = " << (weight * tracker->getWeightedError()).sumSquare() << std::endl;
}

}

if (numFeatures >= 6) {
Expand Down
39 changes: 18 additions & 21 deletions modules/tracker/rbt/src/drift/vpRBProbabilistic3DDriftDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,22 +33,20 @@
#include <visp3/rbt/vpRBProbabilistic3DDriftDetector.h>

#include <visp3/core/vpRect.h>

#include <visp3/rbt/vpRBFeatureTracker.h>
#include <visp3/core/vpPixelMeterConversion.h>
#include <visp3/core/vpDisplay.h>

#include <visp3/rbt/vpRBFeatureTracker.h>

#if defined(VISP_HAVE_NLOHMANN_JSON)
#include <nlohmann/json.hpp>
#endif

void vpRBProbabilistic3DDriftDetector::update(const vpRBFeatureTrackerInput &previousFrame, const vpRBFeatureTrackerInput &frame, const vpHomogeneousMatrix &cTo, const vpHomogeneousMatrix &cprevTo)
{

const vpTranslationVector t = cprevTo.inverse().getTranslationVector();

if (m_points.size() > 0) {

// Step 0: project all points
#ifdef VISP_HAVE_OPENMP
#pragma omp parallel for
Expand All @@ -62,10 +60,10 @@ void vpRBProbabilistic3DDriftDetector::update(const vpRBFeatureTrackerInput &pre
for (vpStored3DSurfaceColorPoint &p : m_points) {
p.visible = true;
if (
p.projPrevPx[0] < 2 || p.projPrevPx[0] >= frame.IRGB.getWidth() - 2
|| p.projPrevPx[1] < 2 || p.projPrevPx[1] >= frame.IRGB.getHeight() - 2
|| p.projCurrPx[0] < 2 || p.projCurrPx[0] >= frame.IRGB.getWidth() - 2
|| p.projCurrPx[1] < 2 || p.projCurrPx[1] >= frame.IRGB.getHeight() - 2) {
p.projPrevPx[0] < 2 || static_cast<unsigned int>(p.projPrevPx[0]) >= frame.IRGB.getWidth() - 2
|| p.projPrevPx[1] < 2 || static_cast<unsigned int>(p.projPrevPx[1]) >= frame.IRGB.getHeight() - 2
|| p.projCurrPx[0] < 2 || static_cast<unsigned int>(p.projCurrPx[0]) >= frame.IRGB.getWidth() - 2
|| p.projCurrPx[1] < 2 || static_cast<unsigned int>(p.projCurrPx[1]) >= frame.IRGB.getHeight() - 2) {
p.visible = false; // Point is outside of either current or previous image, ignore it
continue;
}
Expand Down Expand Up @@ -109,18 +107,17 @@ void vpRBProbabilistic3DDriftDetector::update(const vpRBFeatureTrackerInput &pre
}
}


if (visiblePoints.size() > 0) {
// Compute sample weight
double maxTrace = 0.0;

for (vpStored3DSurfaceColorPoint *p : visiblePoints) {
double trace = p->stats.trace();
if (trace > maxTrace) {
maxTrace = trace;
}
}
maxTrace = std::max(maxTrace, 80.0);
// // Compute sample weight
// double maxTrace = 0.0;

// for (vpStored3DSurfaceColorPoint *p : visiblePoints) {
// double trace = p->stats.trace();
// if (trace > maxTrace) {
// maxTrace = trace;
// }
// }
// maxTrace = std::max(maxTrace, 80.0);
double weightSum = 0.0;
m_score = 0.0;
for (vpStored3DSurfaceColorPoint *p : visiblePoints) {
Expand Down Expand Up @@ -183,8 +180,8 @@ void vpRBProbabilistic3DDriftDetector::update(const vpRBFeatureTrackerInput &pre

for (unsigned int i = frame.renders.boundingBox.getTop(); i < frame.renders.boundingBox.getBottom(); i += 2) {
for (unsigned int j = frame.renders.boundingBox.getLeft(); j < frame.renders.boundingBox.getRight(); j += 2) {
double u = j, v = i;
double x, y;
double u = static_cast<double>(j), v = static_cast<double>(i);
double x = 0.0, y = 0.0;
double Z = frame.renders.depth[i][j];
if (Z > 0.f) {
vpPixelMeterConversion::convertPoint(frame.cam, u, v, x, y);
Expand Down
Loading

0 comments on commit 25635f9

Please sign in to comment.