From 8cbee82dc0438f0d7c0ad450db9da4f356cfac4c Mon Sep 17 00:00:00 2001 From: Samuel Felton Date: Tue, 24 Sep 2024 13:19:56 +0200 Subject: [PATCH] Setup testing rbt module, testing basic configuration/user api --- modules/tracker/rbt/CMakeLists.txt | 10 + .../include/visp3/rbt/vpRBDenseDepthTracker.h | 6 +- .../visp3/rbt/vpRBSilhouetteCCDTracker.h | 13 +- .../visp3/rbt/vpRBSilhouetteMeTracker.h | 79 ++- .../rbt/include/visp3/rbt/vpRBTracker.h | 21 +- modules/tracker/rbt/src/core/vpRBTracker.cpp | 98 +-- .../src/features/vpRBSilhouetteCCDTracker.cpp | 6 +- modules/tracker/rbt/test/testRBT.cpp | 569 ++++++++++++++++++ script/make-coverage-report.sh | 2 +- .../render-based/tutorial-rbt-realsense.cpp | 1 + .../render-based/tutorial-rbt-sequence.cpp | 2 +- 11 files changed, 750 insertions(+), 57 deletions(-) create mode 100644 modules/tracker/rbt/test/testRBT.cpp mode change 100644 => 100755 script/make-coverage-report.sh diff --git a/modules/tracker/rbt/CMakeLists.txt b/modules/tracker/rbt/CMakeLists.txt index 0eaf25f726..bb1851c748 100644 --- a/modules/tracker/rbt/CMakeLists.txt +++ b/modules/tracker/rbt/CMakeLists.txt @@ -53,6 +53,12 @@ if(WITH_SIMDLIB) list(APPEND opt_libs_private ${SIMDLIB_LIBRARIES}) endif() +if(WITH_CATCH2) + # catch2 is private + include_directories(${CATCH2_INCLUDE_DIRS}) +endif() + + 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() @@ -60,3 +66,7 @@ vp_module_include_directories(${opt_incs}) vp_create_module(${opt_libs}) vp_add_tests(DEPENDS_ON visp_core visp_gui visp_io) + +if(VISP_DATASET_FOUND) + +endif() diff --git a/modules/tracker/rbt/include/visp3/rbt/vpRBDenseDepthTracker.h b/modules/tracker/rbt/include/visp3/rbt/vpRBDenseDepthTracker.h index be8d43ece2..91aa59e4fb 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpRBDenseDepthTracker.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpRBDenseDepthTracker.h @@ -184,9 +184,9 @@ class VISP_EXPORT vpRBDenseDepthTracker : public vpRBFeatureTracker virtual void loadJsonConfiguration(const nlohmann::json &j) VP_OVERRIDE { vpRBFeatureTracker::loadJsonConfiguration(j); - m_step = j.value("step", m_step); - m_useMask = j.value("useMask", m_useMask); - m_minMaskConfidence = j.value("minMaskConfidence", m_minMaskConfidence); + setStep(j.value("step", m_step)); + setShouldUseMask(j.value("useMask", m_useMask)); + setMinimumMaskConfidence(j.value("minMaskConfidence", m_minMaskConfidence)); } #endif diff --git a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h index db48267f13..1564f1d5b5 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteCCDTracker.h @@ -142,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 (!gammaj.is_array() || gammaj.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]; @@ -211,7 +211,14 @@ class VISP_EXPORT vpRBSilhouetteCCDTracker : public vpRBFeatureTracker * * @param factor the new temporal smoothing factor. Should be greater than 0 */ - void setTemporalSmoothingFactor(double factor) { m_temporalSmoothingFac = factor; } + void setTemporalSmoothingFactor(double factor) + { + if (factor < 0.0) { + throw vpException(vpException::badValue, "Temporal smoothing factor should be equal to or greater than 0"); + } + m_temporalSmoothingFac = factor; + + } /** * @} */ @@ -238,7 +245,7 @@ class VISP_EXPORT vpRBSilhouetteCCDTracker : public vpRBFeatureTracker { vpRBFeatureTracker::loadJsonConfiguration(j); m_vvsConvergenceThreshold = j.value("convergenceThreshold", m_vvsConvergenceThreshold); - m_temporalSmoothingFac = j.value("temporalSmoothing", m_temporalSmoothingFac); + setTemporalSmoothingFactor(j.value("temporalSmoothing", m_temporalSmoothingFac)); m_ccdParameters = j.value("ccd", m_ccdParameters); } diff --git a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteMeTracker.h b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteMeTracker.h index 580fbf92c6..44c41d331e 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteMeTracker.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpRBSilhouetteMeTracker.h @@ -84,21 +84,90 @@ class VISP_EXPORT vpRBSilhouetteMeTracker : public vpRBFeatureTracker void display(const vpCameraParameters &cam, const vpImage &I, const vpImage &IRGB, const vpImage &depth, const vpRBFeatureDisplayType type) const VP_OVERRIDE; + /** + * \name Settings + * @{ + */ + const vpMe &getMe() const { return m_me; } + vpMe &getMe() { return m_me; } + + unsigned int getNumCandidates() const { return m_numCandidates; } + void setNumCandidates(unsigned int candidates) + { + if (candidates == 0) { + throw vpException(vpException::badValue, "Cannot set a number of candidates equal to zero"); + } + m_numCandidates = candidates; + } + + double getMinRobustThreshold() const { return m_robustMadMin; } + void setMinRobustThreshold(double threshold) + { + if (threshold < 0) { + throw vpException(vpException::badValue, "Robust M estimator min threshold should be greater or equal to 0."); + } + m_robustMadMin = threshold; + } + + /** + * \brief Returns whether the tracking algorithm should filter out points that are unlikely to be on the object according to the mask. + * If the mask is not computed beforehand, then it has no effect + */ + bool shouldUseMask() const { return m_useMask; } + void setShouldUseMask(bool useMask) { m_useMask = useMask; } + + /** + * \brief Returns the minimum mask confidence that a pixel linked to depth point should have if it should be kept during tracking. + * + * This value is between 0 and 1 + */ + float getMinimumMaskConfidence() const { return m_minMaskConfidence; } + void setMinimumMaskConfidence(float confidence) + { + if (confidence > 1.f || confidence < 0.f) { + throw vpException(vpException::badValue, "Mask confidence should be between 0 and 1"); + } + m_minMaskConfidence = confidence; + } + + double getSinglePointConvergenceThreshold() const { return m_singlePointConvergedThresholdPixels; } + void setSinglePointConvergenceThreshold(double threshold) + { + if (threshold < 0.0) { + throw vpException(vpException::badValue, "Convergence threshold should be null or positive"); + } + m_singlePointConvergedThresholdPixels = threshold; + } + + double getGlobalConvergenceMinimumRatio() const { return m_globalVVSConvergenceThreshold; } + void setGlobalConvergenceMinimumRatio(double threshold) + { + if (threshold < 0.0 || threshold > 1.0) { + throw vpException(vpException::badValue, "Minimum converged ratio be between 0 and 1"); + } + m_globalVVSConvergenceThreshold = threshold; + } + #if defined(VISP_HAVE_NLOHMANN_JSON) virtual void loadJsonConfiguration(const nlohmann::json &j) VP_OVERRIDE { vpRBFeatureTracker::loadJsonConfiguration(j); - m_numCandidates = j.value("numCandidates", m_numCandidates); - m_singlePointConvergedThresholdPixels = j.value("convergencePixelThreshold", m_singlePointConvergedThresholdPixels); - m_globalVVSConvergenceThreshold = j.value("convergenceRatio", m_globalVVSConvergenceThreshold); + setNumCandidates(j.value("numCandidates", m_numCandidates)); + setSinglePointConvergenceThreshold(j.value("convergencePixelThreshold", m_singlePointConvergedThresholdPixels)); + setGlobalConvergenceMinimumRatio(j.value("convergenceRatio", m_globalVVSConvergenceThreshold)); m_me = j.value("movingEdge", m_me); - m_useMask = j.value("useMask", m_useMask); - m_minMaskConfidence = j.value("minMaskConfidence", m_minMaskConfidence); + setShouldUseMask(j.value("useMask", m_useMask)); + setMinimumMaskConfidence(j.value("minMaskConfidence", m_minMaskConfidence)); // m_me.setThresholdMarginRatio(-1.0); // m_me.setMinThreshold(-1.0); } #endif + /** + * \name Settings + * @} + */ + private: std::vector m_controlPoints; diff --git a/modules/tracker/rbt/include/visp3/rbt/vpRBTracker.h b/modules/tracker/rbt/include/visp3/rbt/vpRBTracker.h index ed66edc3db..26176f6099 100644 --- a/modules/tracker/rbt/include/visp3/rbt/vpRBTracker.h +++ b/modules/tracker/rbt/include/visp3/rbt/vpRBTracker.h @@ -93,11 +93,15 @@ class VISP_EXPORT vpRBTracker * @{ */ void addTracker(std::shared_ptr tracker); - void loadObjectModel(const std::string &file); + void setupRenderer(const std::string &file); + void setModelPath(const std::string &path); vpCameraParameters getCameraParameters() const; void setCameraParameters(const vpCameraParameters &cam, unsigned h, unsigned w); + unsigned int getImageWidth() const { return m_imageWidth; } + unsigned int getImageHeight() const { return m_imageHeight; } + vpSilhouettePointsExtractionSettings getSilhouetteExtractionParameters() const { return m_depthSilhouetteSettings; @@ -114,13 +118,19 @@ class VISP_EXPORT vpRBTracker m_lambda = lambda; } unsigned int getMaxOptimizationIters() const { return m_vvsIterations; } - void setMaxOptimizationIters(unsigned int iters) { m_vvsIterations = iters; } + void setMaxOptimizationIters(unsigned int iters) + { + if (iters == 0) { + throw vpException(vpException::badValue, "Max number of iterations must be greater than zero"); + } + m_vvsIterations = iters; + } double getOptimizationInitialMu() const { return m_muInit; } void setOptimizationInitialMu(double mu) { if (mu < 0.0) { - throw vpException(vpException::badValue, "Optimization gain should be greater to zero"); + throw vpException(vpException::badValue, "Optimization gain should be greater or equal to zero"); } m_muInit = mu; } @@ -129,7 +139,7 @@ class VISP_EXPORT vpRBTracker void setOptimizationMuIterFactor(double factor) { if (factor < 0.0) { - throw vpException(vpException::badValue, "Optimization gain should be greater to zero"); + throw vpException(vpException::badValue, "Optimization gain should be greater or equal to zero"); } m_muIterFactor = factor; } @@ -157,10 +167,12 @@ class VISP_EXPORT vpRBTracker void reset(); + /** * \name Tracking * @{ */ + void startTracking(); void track(const vpImage &I); void track(const vpImage &I, const vpImage &IRGB); void track(const vpImage &I, const vpImage &IRGB, const vpImage &depth); @@ -211,6 +223,7 @@ class VISP_EXPORT vpRBTracker vpRBFeatureTrackerInput m_currentFrame; vpRBFeatureTrackerInput m_previousFrame; + std::string m_modelPath; vpHomogeneousMatrix m_cMo; vpHomogeneousMatrix m_cMoPrev; vpCameraParameters m_cam; diff --git a/modules/tracker/rbt/src/core/vpRBTracker.cpp b/modules/tracker/rbt/src/core/vpRBTracker.cpp index 519643f3c0..9277a47127 100644 --- a/modules/tracker/rbt/src/core/vpRBTracker.cpp +++ b/modules/tracker/rbt/src/core/vpRBTracker.cpp @@ -35,16 +35,15 @@ #endif #include +#include #include #include #include -#include #include #include #include - #include #define VP_DEBUG_RB_TRACKER 1 @@ -57,18 +56,13 @@ vpRBTracker::vpRBTracker() : m_firstIteration(true), m_trackers(0), m_lambda(1.0 const std::shared_ptr geometryRenderer = std::make_shared( vpPanda3DGeometryRenderer::vpRenderType::OBJECT_NORMALS); - //geometryRenderer->setRenderOrder(-1000); m_renderer.addSubRenderer(geometryRenderer); - // std::shared_ptr blur = std::make_shared( - // "depthBlur", geometryRenderer, true); - // m_renderer.addSubRenderer(blur); - m_renderer.addSubRenderer(std::make_shared( - "depthCanny", geometryRenderer, true, 0.0)); - //m_renderer.addSubRenderer(std::make_shared(false)); + m_renderer.setRenderParameters(m_rendererSettings); m_driftDetector = nullptr; + m_mask = nullptr; } void vpRBTracker::getPose(vpHomogeneousMatrix &cMo) const @@ -110,6 +104,16 @@ vpCameraParameters vpRBTracker::getCameraParameters() const { return m_cam; } void vpRBTracker::setCameraParameters(const vpCameraParameters &cam, unsigned h, unsigned w) { + if (cam.get_projModel() != vpCameraParameters::vpCameraParametersProjType::perspectiveProjWithoutDistortion) { + throw vpException(vpException::badValue, + "Camera model cannot have distortion. Undistort images before tracking and use the undistorted camera model"); + } + if (h == 0 || w == 0) { + throw vpException( + vpException::badValue, + "Image dimensions must be greater than 0" + ); + } m_cam = cam; m_imageHeight = h; m_imageWidth = w; @@ -128,13 +132,29 @@ void vpRBTracker::reset() m_firstIteration = true; } -void vpRBTracker::loadObjectModel(const std::string &file) +void vpRBTracker::setModelPath(const std::string &path) +{ + m_modelPath = path; +} + +void vpRBTracker::setupRenderer(const std::string &file) { + if (!vpIoTools::checkFilename(file)) { + throw vpException("3D model file %s could not be found", file.c_str()); + } + bool requiresSilhouetteShader = false; + for (std::shared_ptr &tracker: m_trackers) { + if (tracker->requiresSilhouetteCandidates()) { + requiresSilhouetteShader = true; + break; + } + } + if (requiresSilhouetteShader) { + m_renderer.addSubRenderer(std::make_shared( + "depthCanny", geometryRenderer, true, 0.0)); + } m_renderer.initFramework(); - //m_renderer.enableSharedDepthBuffer(*m_renderer.getRenderer()); m_renderer.addLight(vpPanda3DAmbientLight("ambient", vpRGBf(0.4f))); - //m_renderer.addLight(vpPanda3DDirectionalLight("dir", vpRGBf(1.f), vpColVector({ 0.0, -0.0, 1.0 }))); - //m_renderer.addLight(vpPanda3DPointLight("point", vpRGBf(8.f), vpColVector({ 0.0, 0.1, 0.1 }), vpColVector({ 1.0, 0.0, 0.0 }))); m_renderer.addNodeToScene(m_renderer.loadObject("object", file)); m_renderer.setFocusedObject("object"); } @@ -169,6 +189,11 @@ void vpRBTracker::track(const vpImage &I, const vpImage & track(frameInput); } +void vpRBTracker::startTracking() +{ + setupRenderer(m_modelPath); +} + void vpRBTracker::track(const vpImage &I, const vpImage &IRGB, const vpImage &depth) { checkDimensionsOrThrow(I, "grayscale"); @@ -477,6 +502,9 @@ std::vector vpRBTracker::extractSilhouettePoints( void vpRBTracker::addTracker(std::shared_ptr tracker) { + if (tracker == nullptr) { + throw vpException(vpException::badValue, "Adding tracker: tracker cannot be null"); + } m_trackers.push_back(tracker); } @@ -554,43 +582,36 @@ void vpRBTracker::loadConfigurationFile(const std::string &filename) } void vpRBTracker::loadConfiguration(const nlohmann::json &j) { - std::cout << "Loading configuration file" << std::endl; m_firstIteration = true; - nlohmann::json cameraSettings = j.at("camera"); + const nlohmann::json cameraSettings = j.at("camera"); m_cam = cameraSettings.at("intrinsics"); m_imageHeight = cameraSettings.value("height", m_imageHeight); m_imageWidth = cameraSettings.value("width", m_imageWidth); - m_rendererSettings.setCameraIntrinsics(m_cam); - m_rendererSettings.setImageResolution(m_imageHeight, m_imageWidth); - m_renderer.setRenderParameters(m_rendererSettings); + setCameraParameters(m_cam, m_imageHeight, m_imageWidth); - std::cout << "Loading object" << std::endl; if (j.contains("model")) { - loadObjectModel(j.at("model")); + setModelPath(j.at("model")); } - //TODO: Clear Panda3D renderer list? - std::cout << "Loading vvs settings" << std::endl; - nlohmann::json vvsSettings = j.at("vvs"); - m_vvsIterations = vvsSettings.value("maxIterations", m_vvsIterations); - m_lambda = vvsSettings.value("gain", m_lambda); - m_muInit = vvsSettings.value("mu", m_muInit); - m_muIterFactor = vvsSettings.value("muIterFactor", m_muIterFactor); - + const nlohmann::json vvsSettings = j.at("vvs"); + m_vvsIterations = setMaxOptimizationIters(vvsSettings.value("maxIterations", m_vvsIterations)); + m_lambda = setOptimizationGain(vvsSettings.value("gain", m_lambda)); + m_muInit = setOptimizationInitialMu(vvsSettings.value("mu", m_muInit)); + m_muIterFactor = setOptimizationMuIterFactor(vvsSettings.value("muIterFactor", m_muIterFactor)); - - std::cout << "Loading silhouette extraction settings" << std::endl; m_depthSilhouetteSettings = j.at("silhouetteExtractionSettings"); - - std::cout << "Loading the different trackers" << std::endl;; m_trackers.clear(); nlohmann::json features = j.at("features"); vpRBFeatureTrackerFactory &featureFactory = vpRBFeatureTrackerFactory::getFactory(); for (const nlohmann::json &trackerSettings: features) { std::shared_ptr tracker = featureFactory.buildFromJson(trackerSettings); if (tracker == nullptr) { - throw vpException(vpException::badValue, "Cannot instanciate subtracker with the current settings, make sure that the type is registered. Settings: %s", trackerSettings.dump(2).c_str()); + throw vpException( + vpException::badValue, + "Cannot instantiate subtracker with the current settings, make sure that the type is registered. Settings: %s", + trackerSettings.dump(2).c_str() + ); } m_trackers.push_back(tracker); } @@ -600,7 +621,10 @@ void vpRBTracker::loadConfiguration(const nlohmann::json &j) nlohmann::json maskSettings = j.at("mask"); m_mask = maskFactory.buildFromJson(maskSettings); if (m_mask == nullptr) { - throw vpException(vpException::badValue, "Cannot instanciate object mask with the current settings, make sure that the type is registered. Settings: %s", maskSettings.dump(2).c_str()); + throw vpException( + vpException::badValue, + "Cannot instantiate object mask with the current settings, make sure that the type is registered. Settings: %s", + maskSettings.dump(2).c_str()); } } if (j.contains("drift")) { @@ -608,7 +632,10 @@ void vpRBTracker::loadConfiguration(const nlohmann::json &j) nlohmann::json driftSettings = j.at("drift"); m_driftDetector = factory.buildFromJson(driftSettings); if (m_driftDetector == nullptr) { - throw vpException(vpException::badValue, "Cannot instantiate drift detection with the current settings, make sure that the type is registered in the factory"); + throw vpException( + vpException::badValue, + "Cannot instantiate drift detection with the current settings, make sure that the type is registered in the factory" + ); } } } @@ -622,7 +649,6 @@ void vpRBTracker::initClick(const vpImage &I, const std::string & initializer.initClick(I, initFile, displayHelp); m_cMo = initializer.getPose(); } - #endif END_VISP_NAMESPACE diff --git a/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp b/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp index d1cbdb5fea..b044f6524d 100644 --- a/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp +++ b/modules/tracker/rbt/src/features/vpRBSilhouetteCCDTracker.cpp @@ -161,8 +161,6 @@ void vpRBSilhouetteCCDTracker::computeVVSIter(const vpRBFeatureTrackerInput &fra } } - - void vpRBSilhouetteCCDTracker::display(const vpCameraParameters &/*cam*/, const vpImage &/*I*/, const vpImage &IRGB, const vpImage &/*depth*/, const vpRBFeatureDisplayType type) const { unsigned normal_points_number = floor(m_ccdParameters.h / m_ccdParameters.delta_h); @@ -375,7 +373,7 @@ void vpRBSilhouetteCCDTracker::computeLocalStatistics(const vpImage &I, normalized_param[kk][1] += vic_ptr[10 * negative_normal + 7]; } - } + } #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif @@ -491,7 +489,7 @@ void vpRBSilhouetteCCDTracker::computeLocalStatistics(const vpImage &I, } } -} + } void vpRBSilhouetteCCDTracker::computeErrorAndInteractionMatrix() { diff --git a/modules/tracker/rbt/test/testRBT.cpp b/modules/tracker/rbt/test/testRBT.cpp new file mode 100644 index 0000000000..cdbc169292 --- /dev/null +++ b/modules/tracker/rbt/test/testRBT.cpp @@ -0,0 +1,569 @@ +/* + * ViSP, open source Visual Servoing Platform software. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. + * + * This software is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * See the file LICENSE.txt at the root directory of this source + * distribution for additional information about the GNU GPL. + * + * For using ViSP with software that can not be combined with the GNU + * GPL, please contact Inria about acquiring a ViSP Professional + * Edition License. + * + * See https://visp.inria.fr for more information. + * + * This software was developed at: + * Inria Rennes - Bretagne Atlantique + * Campus Universitaire de Beaulieu + * 35042 Rennes Cedex + * France + * + * If you have questions regarding the use of this file, please contact + * Inria at visp@inria.fr + * + * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE + * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. + * + * Description: + * Test vpMbGenericTracker JSON parse / save. + */ + +/*! + \file testMbtJsonSettings.cpp + + Test test saving and parsing JSON configuration for vpMbGenericTracker +*/ + +#include +#include + +#include +#include +#include +#include + + + +#if defined(VISP_HAVE_CATCH2) + +#if defined(VISP_HAVE_NLOHMANN_JSON) +#include +#endif + +#define CATCH_CONFIG_RUNNER +#include + +SCENARIO("Instanciating a silhouette me tracker", "[rbt]") +{ + GIVEN("A base me tracker") + { + vpRBSilhouetteMeTracker tracker; + WHEN("Changing mask parameters") + { + THEN("Enabling mask is seen") + { + bool useMaskDefault = tracker.shouldUseMask(); + tracker.setShouldUseMask(!useMaskDefault); + REQUIRE(useMaskDefault != tracker.shouldUseMask()); + } + THEN("Changing mask min confidence with a correct value is Ok") + { + tracker.setMinimumMaskConfidence(0.0); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.0); + tracker.setMinimumMaskConfidence(1.0); + REQUIRE(tracker.getMinimumMaskConfidence() == 1.0); + tracker.setMinimumMaskConfidence(0.5); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.5); + } + THEN("Setting incorrect mask confidence value fails") + { + REQUIRE_THROWS(tracker.setMinimumMaskConfidence(-1.0)); + } + } + WHEN("Changing robust threshold") + { + THEN("Setting correct value works") + { + tracker.setMinRobustThreshold(0.5); + REQUIRE(tracker.getMinRobustThreshold() == 0.5); + } + THEN("Setting negative value throws") + { + REQUIRE_THROWS(tracker.setMinRobustThreshold(-0.5)); + } + } + WHEN("Changing number of candidates") + { + THEN("Setting correct value works") + { + tracker.setNumCandidates(3); + REQUIRE(tracker.getNumCandidates() == 3); + } + THEN("Setting incorrect value throws") + { + REQUIRE_THROWS(tracker.setNumCandidates(0)); + } + } + WHEN("Changing convergence settings") + { + THEN("Setting correct single point value works") + { + tracker.setSinglePointConvergenceThreshold(1.0); + REQUIRE(tracker.getSinglePointConvergenceThreshold() == 1.0); + } + THEN("Setting incorrect single point value throws") + { + REQUIRE_THROWS(tracker.setSinglePointConvergenceThreshold(-1.0)); + } + THEN("Setting correct global value works") + { + tracker.setGlobalConvergenceMinimumRatio(0.0); + REQUIRE(tracker.getGlobalConvergenceMinimumRatio() == 0.0); + tracker.setGlobalConvergenceMinimumRatio(1.0); + REQUIRE(tracker.getGlobalConvergenceMinimumRatio() == 1.0); + tracker.setGlobalConvergenceMinimumRatio(0.5); + REQUIRE(tracker.getGlobalConvergenceMinimumRatio() == 0.5); + } + } +#if defined(VISP_HAVE_NLOHMANN_JSON) + WHEN("defining JSON parameters") + { + + nlohmann::json j = { + {"type", "silhouetteMe"}, + { "numCandidates", 1 }, + { "weight", 0.5 }, + { "convergencePixelThreshold", 0.5 }, + { "convergenceRatio", 0.99}, + { "useMask", true}, + { "minMaskConfidence", 0.5}, + { "movingEdge", { + {"maskSign", 0}, + {"maskSize" , 5}, + {"minSampleStep" , 4.0}, + {"mu" , {0.5, 0.5}}, + {"nMask" , 90}, + {"ntotalSample" , 0}, + {"pointsToTrack" , 200}, + {"range" , 5}, + {"sampleStep" , 4.0}, + {"strip" , 2}, + {"thresholdType" , "normalized"}, + {"threshold" , 20.0} + }} + }; + THEN("Loading correct settings works") + { + tracker.loadJsonConfiguration(j); + REQUIRE(tracker.getNumCandidates() == 1); + REQUIRE(tracker.shouldUseMask() == true); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.5); + REQUIRE(tracker.getMe().getMaskNumber() == 90); + REQUIRE(tracker.getMe().getThreshold() == 20.0); + } + THEN("Setting incorrect candidate number throws") + { + j["numCandidates"] = 0; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + THEN("Setting incorrect mask confidence throws") + { + j["minMaskConfidence"] = 5.0; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + THEN("Setting incorrect single point convergence vlaue confidence throws") + { + j["convergencePixelThreshold"] = -1.0; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + THEN("Setting incorrect global convergence vlaue confidence throws") + { + j["convergenceRatio"] = 2.0; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + } + } +#endif +} + +SCENARIO("Instanciating a silhouette CCD tracker", "[rbt]") +{ + vpRBSilhouetteCCDTracker tracker; + WHEN("Setting smoothing factor") + { + THEN("Setting value above 0 works") + { + tracker.setTemporalSmoothingFactor(0.5); + REQUIRE(tracker.getTemporalSmoothingFactor() == 0.5); + } + THEN("Setting value below 0 throws") + { + REQUIRE_THROWS(tracker.setTemporalSmoothingFactor(-2.0)); + } + } + WHEN("Updating CCD parameters") + { + vpCCDParameters ccd = tracker.getCCDParameters(); + ccd.h += 4; + ccd.delta_h += 2; + tracker.setCCDParameters(ccd); + THEN("Changes are propagated to tracker") + { + REQUIRE(tracker.getCCDParameters().h == ccd.h); + REQUIRE(tracker.getCCDParameters().delta_h == ccd.delta_h); + } + + } + +#if defined(VISP_HAVE_NLOHMANN_JSON) + WHEN("Defining associated json") + { + nlohmann::json j = { + {"type", "silhouetteCCD"}, + {"weight", 0.01}, + {"temporalSmoothing", 0.1}, + {"convergenceThreshold", 0.1}, + {"ccd", { + {"h", 64}, + {"delta_h", 16}, + {"gamma", { 0.1, 0.2, 0.3, 0.4 } } + }} + }; + THEN("Loading correct json works") + { + tracker.loadJsonConfiguration(j); + REQUIRE(tracker.getTemporalSmoothingFactor() == 0.1); + vpCCDParameters ccd = tracker.getCCDParameters(); + REQUIRE(ccd.h == 64); + REQUIRE(ccd.delta_h == 16); + REQUIRE((ccd.gamma_1 == 0.1 && ccd.gamma_2 == 0.2 && ccd.gamma_3 == 0.3 && ccd.gamma_4 == 0.4)); + } + THEN("Loading invalid temporal smoothing factor throws") + { + j["temporalSmoothing"] = -3.14; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + THEN("Loading invalid ccd gamma throws") + { + j["ccd"]["gamma"] = -3.14; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + } +#endif +} + +#if defined(VP_HAVE_RB_KLT_TRACKER) +SCENARIO("Instanciating KLT tracker") +{ + vpRBKltTracker tracker; + WHEN("Modifying basic settings") + { + tracker.setFilteringBorderSize(2); + tracker.setFilteringMaxReprojectionError(0.024); + tracker.setMinimumDistanceNewPoints(0.005); + tracker.setMinimumNumberOfPoints(20); + tracker.setShouldUseMask(true); + tracker.setMinimumMaskConfidence(0.5); + THEN("Every change is visible") + { + REQUIRE(tracker.getFilteringBorderSize() == 2); + REQUIRE(tracker.getFilteringMaxReprojectionError() == 0.024); + REQUIRE(tracker.getMinimumDistanceNewPoints() == 0.005); + REQUIRE(tracker.getMinimumNumberOfPoints() == 20); + REQUIRE(tracker.shouldUseMask()); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.5); + } + THEN("Setting incorrect Mask confidence throws") + { + REQUIRE_THROWS(tracker.setMinimumMaskConfidence(-1.0)); + } + } + +#if defined(VISP_HAVE_NLOHMANN_JSON) + WHEN("Defining associated json") + { + + nlohmann::json j = { + {"type", "klt"}, + {"weight", 0.01}, + {"minimumNumPoints", 25}, + {"newPointsMinPixelDistance", 5}, + {"maxReprojectionErrorPixels", 0.01}, + {"useMask", true}, + {"minMaskConfidence", 0.1}, + { "windowSize", 7 }, + { "quality", 0.01 }, + { "maxFeatures", 500 } + }; + THEN("Loading correct json works") + { + tracker.loadJsonConfiguration(j); + REQUIRE(tracker.getMinimumNumberOfPoints() == 25); + REQUIRE(tracker.getMinimumDistanceNewPoints() == 5); + REQUIRE(tracker.getFilteringMaxReprojectionError() == 0.01); + REQUIRE(tracker.shouldUseMask() == true); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.1f); + REQUIRE(tracker.getKltTracker().getWindowSize() == 7); + REQUIRE(tracker.getKltTracker().getQuality() == 0.01); + REQUIRE(tracker.getKltTracker().getMaxFeatures() == 500); + } + THEN("Loading invalid mask confidence throws") + { + j["minMaskConfidence"] = -3.14; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + } +#endif +} +#endif + +SCENARIO("Instanciating depth tracker", "[rbt]") +{ + vpRBDenseDepthTracker tracker; + WHEN("Setting steps") + { + THEN("Setting positive value works") + { + tracker.setStep(4); + REQUIRE(tracker.getStep() == 4); + } + THEN("Setting 0 step is invalid") + { + REQUIRE_THROWS(tracker.setStep(0)); + } + } + WHEN("Setting confidence") + { + THEN("Setting incorrect mask confidence value") + { + REQUIRE_THROWS(tracker.setMinimumMaskConfidence(-1.0)); + } + THEN("Setting correct mask confidence value") + { + tracker.setMinimumMaskConfidence(0.8); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.8f); + } + THEN("Toggling mask works") + { + tracker.setShouldUseMask(true); + REQUIRE(tracker.shouldUseMask()); + } + } +#if defined(VISP_HAVE_NLOHMANN_JSON) + WHEN("Defining associated json") + { + + nlohmann::json j = { + {"type", "klt"}, + {"weight", 0.01}, + {"step", 16}, + {"useMask", true}, + {"minMaskConfidence", 0.1} + }; + THEN("Loading correct json works") + { + tracker.loadJsonConfiguration(j); + REQUIRE(tracker.getStep() == 16); + REQUIRE(tracker.shouldUseMask()); + REQUIRE(tracker.getMinimumMaskConfidence() == 0.1f); + } + THEN("Loading invalid mask confidence throws") + { + j["minMaskConfidence"] = -3.14; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + THEN("Loading invalid step throws") + { + j["step"] = 0; + REQUIRE_THROWS(tracker.loadJsonConfiguration(j)); + } + } +#endif +} + +SCENARIO("Instanciating a render-based tracker", "[rbt]") +{ + vpRBTracker tracker; + + WHEN("Setting optimization parameters") + { + THEN("Max num iter cannot be zero") + { + REQUIRE_THROWS(tracker.setMaxOptimizationIters(0)); + } + THEN("Setting num iter is ok") + { + tracker.setMaxOptimizationIters(10); + REQUIRE(tracker.getMaxOptimizationIters() == 10); + } + THEN("Gain cannot be negative") + { + REQUIRE_THROWS(tracker.setOptimizationGain(-0.5)); + } + THEN("Positive gain is ok") + { + tracker.setOptimizationGain(0.5); + REQUIRE(tracker.getOptimizationGain() == 0.5); + } + THEN("Initial mu cannot be negative") + { + REQUIRE_THROWS(tracker.setOptimizationInitialMu(-0.5)); + } + THEN("Initial mu can be zero (gauss newton)") + { + tracker.setOptimizationInitialMu(0.0); + REQUIRE(tracker.getOptimizationInitialMu() == 0.0); + } + THEN("Initial mu can be above zero") + { + tracker.setOptimizationInitialMu(0.1); + REQUIRE(tracker.getOptimizationInitialMu() == 0.1); + } + + THEN("Mu factor cannot be negative") + { + REQUIRE_THROWS(tracker.setOptimizationMuIterFactor(-0.5)); + } + THEN("Mu factor can be zero") + { + tracker.setOptimizationMuIterFactor(0.0); + REQUIRE(tracker.getOptimizationMuIterFactor() == 0.0); + } + THEN("Mu factor can be positive") + { + tracker.setOptimizationMuIterFactor(0.1); + REQUIRE(tracker.getOptimizationMuIterFactor() == 0.1); + } + + + } + + WHEN("Setting camera parameters and resolution") + { + unsigned int h = 480, w = 640; + vpCameraParameters cam(600, 600, 320, 240); + THEN("Image height cannot be zero") + { + REQUIRE_THROWS(tracker.setCameraParameters(cam, 0, w)); + } + THEN("Image width cannot be zero") + { + REQUIRE_THROWS(tracker.setCameraParameters(cam, h, 0)); + } + THEN("Camera model cannot have distortion") + { + cam.initPersProjWithDistortion(600, 600, 320, 240, 0.01, 0.01); + REQUIRE_THROWS(tracker.setCameraParameters(cam, h, w)); + } + THEN("Loading with perspective model with no distortion and correct resolution is ok") + { + tracker.setCameraParameters(cam, h, w); + REQUIRE(tracker.getCameraParameters() == cam); + REQUIRE(tracker.getImageHeight() == h); + REQUIRE(tracker.getImageWidth() == w); + } + } + +#if defined(VISP_HAVE_NLOHMANN_JSON) + WHEN("Loading JSON configuration") + { + const std::string jsonLiteral = R"JSON({ + "camera": { + "intrinsics": { + "model": "perspectiveWithoutDistortion", + "px" : 302.573, + "py" : 302.396, + "u0" : 162.776, + "v0" : 122.475 + }, + "height": 240, + "width" : 320 + }, + "vvs": { + "gain": 1.0, + "maxIterations" : 10 + }, + "model" : "/home/sfelton/Downloads/sinatrack-data/data/cutting_guide/cutting_guide.obj", + "silhouetteExtractionSettings" : { + "threshold": { + "type": "relative", + "value" : 0.1 + }, + "sampling" : { + "type": "fixed", + "numPoints" : 400 + } + }, + "features": { + "silhouetteGeometry": { + "weight" : 0.5, + "numCandidates" : 3, + "convergencePixelThreshold" : 3, + "convergenceRatio" : 0.99, + "movingEdge" : { + "maskSign": 0, + "maskSize" : 5, + "minSampleStep" : 4.0, + "mu" : [ + 0.5, + 0.5 + ] , + "nMask" : 90, + "ntotalSample" : 0, + "pointsToTrack" : 200, + "range" : 5, + "sampleStep" : 4.0, + "strip" : 2, + "thresholdType" : "normalized", + "threshold" : 20.0 + } + }, + "silhouetteColor" : { + "weight" : 0.5, + "convergenceThreshold" : 0.1, + "temporalSmoothing" : 0.1, + "ccd" : { + "h": 4, + "delta_h" : 1 + } + } + } + })JSON"; + nlohmann::json j = nlohmann::json::parse(jsonLiteral); + THEN("Loading configuration with trackers and a 3D model works") + { + tracker.loadConfiguration(j); + REQUIRE(...); + } + THEN("Loading configuration without model also works") + { + j.erase("model"); + tracker.loadConfiguration(j); + REQUIRE(...); + } + } +#endif + +} + + +int main(int argc, char *argv[]) +{ + Catch::Session session; // There must be exactly one instance + session.applyCommandLine(argc, argv); + + int numFailed = session.run(); + return numFailed; +} + +#else + +int main() +{ + return EXIT_SUCCESS; +} + +#endif diff --git a/script/make-coverage-report.sh b/script/make-coverage-report.sh old mode 100644 new mode 100755 index c74d476d7a..9d19d10e46 --- a/script/make-coverage-report.sh +++ b/script/make-coverage-report.sh @@ -18,7 +18,7 @@ fi cd $build_dir lcov --zerocounters --directory . -cmake $source_dir -DBUILD_COVERAGE=ON -DBUILD_DEPRECATED_FUNCTIONS=OFF +cmake $source_dir -DBUILD_COVERAGE=ON -DBUILD_DEPRECATED_FUNCTIONS=OFF -DCMAKE_BUILD_TYPE=Debug cmake --build . --target all -j$(nproc) cmake --build . --target test -j$(nproc) lcov --directory . --capture --output-file visp-coverage.info diff --git a/tutorial/tracking/render-based/tutorial-rbt-realsense.cpp b/tutorial/tracking/render-based/tutorial-rbt-realsense.cpp index 403b76d373..f0aa875c3f 100644 --- a/tutorial/tracking/render-based/tutorial-rbt-realsense.cpp +++ b/tutorial/tracking/render-based/tutorial-rbt-realsense.cpp @@ -81,6 +81,7 @@ int main(int argc, const char **argv) std::cout << "Loading tracker: " << baseArgs.trackerConfiguration << std::endl; vpRBTracker tracker; tracker.loadConfigurationFile(baseArgs.trackerConfiguration); + tracker.startTracking(); const unsigned int width = realsenseArgs.width, height = realsenseArgs.height; const unsigned fps = realsenseArgs.fps; diff --git a/tutorial/tracking/render-based/tutorial-rbt-sequence.cpp b/tutorial/tracking/render-based/tutorial-rbt-sequence.cpp index cc4e7853be..23f376353f 100644 --- a/tutorial/tracking/render-based/tutorial-rbt-sequence.cpp +++ b/tutorial/tracking/render-based/tutorial-rbt-sequence.cpp @@ -77,9 +77,9 @@ int main(int argc, const char **argv) // Set tracking and rendering parameters vpCameraParameters cam; - std::cout << "Creating tracker" << std::endl; vpRBTracker tracker; tracker.loadConfigurationFile(baseArgs.trackerConfiguration); + tracker.startTracking(); cam = tracker.getCameraParameters(); //VideoReader to read images from disk