From 96804f73558b20172e6a1e7bbe07fe209cece878 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Mon, 4 Jan 2021 16:07:36 +0100 Subject: [PATCH 01/21] Balance number of keypoints in a grid --- interfaces/SolARKeypointDetectorOpencv.h | 2 + src/SolARKeypointDetectorOpencv.cpp | 61 +++++++++++++----------- 2 files changed, 35 insertions(+), 28 deletions(-) diff --git a/interfaces/SolARKeypointDetectorOpencv.h b/interfaces/SolARKeypointDetectorOpencv.h index b07c743d..5c210356 100644 --- a/interfaces/SolARKeypointDetectorOpencv.h +++ b/interfaces/SolARKeypointDetectorOpencv.h @@ -87,6 +87,8 @@ class SOLAROPENCV_EXPORT_API SolARKeypointDetectorOpencv : public org::bcom::xpc int m_id; cv::Ptr m_detector; cv::KeyPointsFilter kptsFilter; + int m_nbGridWidth = 20; + int m_nbGridHeight = 20; }; diff --git a/src/SolARKeypointDetectorOpencv.cpp b/src/SolARKeypointDetectorOpencv.cpp index 77a90e81..a32db07c 100644 --- a/src/SolARKeypointDetectorOpencv.cpp +++ b/src/SolARKeypointDetectorOpencv.cpp @@ -54,6 +54,8 @@ SolARKeypointDetectorOpencv::SolARKeypointDetectorOpencv():ConfigurableBase(xpcf declareProperty("nbDescriptors", m_nbDescriptors); declareProperty("threshold", m_threshold); declareProperty("nbOctaves", m_nbOctaves); + declareProperty("nbGridWidth", m_nbGridWidth); + declareProperty("nbGridHeight", m_nbGridHeight); declareProperty("type", m_type); LOG_DEBUG("SolARKeypointDetectorOpencv constructor"); } @@ -95,13 +97,13 @@ void SolARKeypointDetectorOpencv::setType(KeypointDetectorType type) */ m_type=typeToString.at(type); switch (type) { - case (KeypointDetectorType::SIFT): - LOG_DEBUG("KeypointDetectorImp::setType(SIFT)"); - if (m_threshold > 0) - m_detector = SIFT::create(m_nbDescriptors, m_nbOctaves, 0.04, m_threshold); + case (KeypointDetectorType::SIFT): + LOG_DEBUG("KeypointDetectorImp::setType(SIFT)"); + if (m_threshold > 0) + m_detector = SIFT::create(0, m_nbOctaves, m_threshold, 10.0); else - m_detector = SIFT::create(m_nbDescriptors); - break; + m_detector = SIFT::create(4 * m_nbDescriptors); + break; case (KeypointDetectorType::AKAZE): LOG_DEBUG("KeypointDetectorImp::setType(AKAZE)"); if (m_threshold > 0) @@ -119,7 +121,7 @@ void SolARKeypointDetectorOpencv::setType(KeypointDetectorType type) case (KeypointDetectorType::ORB): LOG_DEBUG("KeypointDetectorImp::setType(ORB)"); if (m_nbDescriptors > 0) - m_detector=ORB::create(m_nbDescriptors, 1.2f, m_nbOctaves); + m_detector=ORB::create(100* m_nbDescriptors, 1.2f); else m_detector = ORB::create(); break; @@ -130,9 +132,6 @@ void SolARKeypointDetectorOpencv::setType(KeypointDetectorType type) else m_detector=BRISK::create(); break; - - - default : LOG_DEBUG("KeypointDetectorImp::setType(AKAZE)"); m_detector=AKAZE::create(); @@ -180,22 +179,28 @@ void SolARKeypointDetectorOpencv::detect(const SRef image, std::vectorm_type)); } m_detector->detect(img_1, kpts, Mat()); - // group keypoints according to octave - std::map> kpOctaves; - for (const auto &it : kpts) - kpOctaves[it.octave].push_back(it); - int nbOctaves = static_cast(kpOctaves.size()); - if (nbOctaves > 0) { - int nbKpPerOctave = m_nbDescriptors / nbOctaves; - kpts.clear(); - // get best feature per octave - for (auto it = kpOctaves.rbegin(); it != kpOctaves.rend(); it++) { - nbOctaves--; - if (nbOctaves != 0) - kptsFilter.retainBest(it->second, nbKpPerOctave); - else - kptsFilter.retainBest(it->second, m_nbDescriptors - static_cast(kpts.size())); - kpts.insert(kpts.end(), it->second.begin(), it->second.end()); + // fix scale + for (auto& keypoint : kpts) { + keypoint.pt.x = keypoint.pt.x * ratioInv; + keypoint.pt.y = keypoint.pt.y * ratioInv; + } + // group keypoints according to cells of the grid + std::map> gridKps; + for (const auto &it : kpts) { + int id_width = static_cast(std::floor(it.pt.x * m_nbGridWidth / image->getWidth())); + int id_height = static_cast(std::floor(it.pt.y * m_nbGridHeight / image->getHeight())); + gridKps[id_height * m_nbGridWidth + id_width].push_back(it); + } + // get best feature per cell + kpts.clear(); + int nbCells = static_cast(gridKps.size()); + if (nbCells > 0) { + int countCell(0); + for (auto& it: gridKps) { + int nbKpPerCell = static_cast((m_nbDescriptors - kpts.size()) / (nbCells - countCell)); + kptsFilter.retainBest(it.second, nbKpPerCell); + kpts.insert(kpts.end(), it.second.begin(), it.second.end()); + countCell++; } } } @@ -210,8 +215,8 @@ void SolARKeypointDetectorOpencv::detect(const SRef image, std::vector((int)py, (int)px); From 9f65dbc20e87609d540cea44cae69b2f5d39e942 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Tue, 5 Jan 2021 14:49:26 +0100 Subject: [PATCH 02/21] Fix undistortPoints component --- interfaces/SolARUndistortPointsOpencv.h | 29 ++++++--- src/SolARModuleOpencv.cpp | 7 ++ src/SolARUndistortPointsOpencv.cpp | 87 ++++++++++++++----------- 3 files changed, 75 insertions(+), 48 deletions(-) diff --git a/interfaces/SolARUndistortPointsOpencv.h b/interfaces/SolARUndistortPointsOpencv.h index 0afcc91e..ff3363d4 100644 --- a/interfaces/SolARUndistortPointsOpencv.h +++ b/interfaces/SolARUndistortPointsOpencv.h @@ -16,15 +16,12 @@ #ifndef SOLARUNDISTORTPOINTS_H #define SOLARUNDISTORTPOINTS_H -#include #include "xpcf/component/ComponentBase.h" #include "SolAROpencvAPI.h" #include "api/geom/IUndistortPoints.h" - #include "opencv2/core.hpp" - -#include "SolAROpencvAPI.h" +#include namespace SolAR { namespace MODULES { @@ -45,12 +42,26 @@ class SOLAROPENCV_EXPORT_API SolARUndistortPointsOpencv : public org::bcom::xpcf ~SolARUndistortPointsOpencv() = default; void unloadComponent () override final; - FrameworkReturnCode undistort(const std::vector & inputPoints, std::vector & outputPoints) override; - /// @brief Set the distortion intrinsic camera parameters - void setDistortionParameters(const datastructure::CamDistortion & distortion_parameters) override; - /// @brief Set the intrinsic camera parameters - void setIntrinsicParameters(const datastructure::CamCalibration & intrinsic_parameters) override; + /// @brief This method corrects undistortsion to a set of 2D points + /// @param[in] inputPoints the set of 2D points to correct + /// @param[out] outputPoints the undistorted 2D Points + /// @return FrameworkReturnCode::_SUCCESS_ if 2D transformation succeed, else FrameworkReturnCode::_ERROR. + FrameworkReturnCode undistort(const std::vector & inputPoints, + std::vector & outputPoints) override; + + /// @brief This method corrects undistortsion to a set of 2D keypoints + /// @param[in] inputKeypoints the set of 2D keypoints to correct + /// @param[out] outputKeypoints the undistorted 2D keypoints + /// @return FrameworkReturnCode::_SUCCESS_ if 2D transformation succeed, else FrameworkReturnCode::_ERROR. + FrameworkReturnCode undistort(const std::vector & inputKeypoints, + std::vector & outputKeypoints) override; + + /// @brief this method is used to set intrinsic parameters and distorsion of the camera + /// @param[in] Camera calibration matrix parameters. + /// @param[in] Camera distorsion parameters. + void setCameraParameters(const datastructure::CamCalibration & intrinsicParams, + const datastructure::CamDistortion & distorsionParams) override; private: diff --git a/src/SolARModuleOpencv.cpp b/src/SolARModuleOpencv.cpp index 504edc47..0844f588 100644 --- a/src/SolARModuleOpencv.cpp +++ b/src/SolARModuleOpencv.cpp @@ -60,6 +60,7 @@ #include "SolARSVDFundamentalMatrixDecomposerOpencv.h" #include "SolARSVDTriangulationOpencv.h" #include "SolAR2D3DcorrespondencesFinderOpencv.h" +#include "SolARUndistortPointsOpencv.h" #include "SolARVideoAsCameraOpencv.h" #include "SolARImagesAsCameraOpencv.h" #include "SolARDeviceDataLoader.h" @@ -261,6 +262,10 @@ extern "C" XPCF_MODULEHOOKS_API xpcf::XPCFErrorCode XPCF_getComponent(const boos { errCode = xpcf::tryCreateComponent(componentUUID, interfaceRef); } + if (errCode != xpcf::XPCFErrorCode::_SUCCESS) + { + errCode = xpcf::tryCreateComponent(componentUUID, interfaceRef); + } return errCode; } @@ -285,6 +290,7 @@ XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARGeometricMatchesFilterOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARHomographyEstimationOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARHomographyMatrixDecomposerOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImageConvertorOpencv) +XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImageConvertorUnity) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImageFilterBinaryOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImageFilterAdaptiveBinaryOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImageFilterBlurOpencv) @@ -312,4 +318,5 @@ XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARVideoAsCameraOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImagesAsCameraOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARDeviceDataLoader) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARMapFusionOpencv) +XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARUndistortPointsOpencv) XPCF_END_COMPONENTS_DECLARATION diff --git a/src/SolARUndistortPointsOpencv.cpp b/src/SolARUndistortPointsOpencv.cpp index eb9a98e3..61143398 100644 --- a/src/SolARUndistortPointsOpencv.cpp +++ b/src/SolARUndistortPointsOpencv.cpp @@ -28,18 +28,16 @@ using namespace datastructure; namespace MODULES { namespace OPENCV { - SolARUndistortPointsOpencv::SolARUndistortPointsOpencv():ComponentBase(xpcf::toUUID()) - { - declareInterface(this); - - //internal data for matrix - m_camMatrix.create(3, 3, CV_32FC1); - m_camDistortion.create(5, 1, CV_32FC1); - - } +SolARUndistortPointsOpencv::SolARUndistortPointsOpencv():ComponentBase(xpcf::toUUID()) +{ + declareInterface(this); + //internal data for matrix + m_camMatrix.create(3, 3, CV_32FC1); + m_camDistortion.create(5, 1, CV_32FC1); +} - FrameworkReturnCode SolARUndistortPointsOpencv::undistort(const std::vector & inputPoints, std::vector & outputPoints){ - +FrameworkReturnCode SolARUndistortPointsOpencv::undistort(const std::vector & inputPoints, std::vector & outputPoints) +{ std::vector ptvec; std::vector out_ptvec; @@ -52,40 +50,51 @@ namespace OPENCV { ptvec[k].y = inputPoints[k].getY(); } - cv::undistortPoints(ptvec,out_ptvec, m_camMatrix, m_camDistortion); + cv::undistortPoints(ptvec,out_ptvec, m_camMatrix, m_camDistortion, cv::Mat(), m_camMatrix); for(unsigned int k = 0 ; k < out_ptvec.size() ; k++){ outputPoints[k] = Point2Df( out_ptvec[k].x, out_ptvec[k].y ); } - return FrameworkReturnCode::_SUCCESS; - } - - void SolARUndistortPointsOpencv::setIntrinsicParameters(const CamCalibration & intrinsic_parameters){ - m_intrinsic_parameters = intrinsic_parameters; - - this->m_camMatrix.at(0, 0) = m_intrinsic_parameters(0, 0); - this->m_camMatrix.at(0, 1) = m_intrinsic_parameters(0, 1); - this->m_camMatrix.at(0, 2) = m_intrinsic_parameters(0, 2); - this->m_camMatrix.at(1, 0) = m_intrinsic_parameters(1, 0); - this->m_camMatrix.at(1, 1) = m_intrinsic_parameters(1, 1); - this->m_camMatrix.at(1, 2) = m_intrinsic_parameters(1, 2); - this->m_camMatrix.at(2, 0) = m_intrinsic_parameters(2, 0); - this->m_camMatrix.at(2, 1) = m_intrinsic_parameters(2, 1); - this->m_camMatrix.at(2, 2) = m_intrinsic_parameters(2, 2); - } - - void SolARUndistortPointsOpencv::setDistortionParameters(const CamDistortion & distortion_parameters){ - m_distortion_parameters = distortion_parameters; - - this->m_camDistortion.at(0, 0) = m_distortion_parameters(0); - this->m_camDistortion.at(1, 0) = m_distortion_parameters(1); - this->m_camDistortion.at(2, 0) = m_distortion_parameters(2); - this->m_camDistortion.at(3, 0) = m_distortion_parameters(3); - this->m_camDistortion.at(4, 0) = m_distortion_parameters(4); - } + return FrameworkReturnCode::_SUCCESS; +} - +FrameworkReturnCode SolARUndistortPointsOpencv::undistort(const std::vector & inputKeypoints, std::vector & outputKeypoints) +{ + std::vector inputPoints, outputPoints; + for (const auto &it : inputKeypoints) + inputPoints.push_back(Point2Df(it.getX(), it.getY())); + undistort(inputPoints, outputPoints); + outputKeypoints.resize(inputKeypoints.size()); + for (int i = 0; i < inputKeypoints.size(); ++i) { + Keypoint kp = inputKeypoints[i]; + kp.setX(outputPoints[i].getX()); + kp.setY(outputPoints[i].getY()); + outputKeypoints[i] = kp; + } + return FrameworkReturnCode::_SUCCESS; +} +void SolARUndistortPointsOpencv::setCameraParameters(const datastructure::CamCalibration & intrinsicParams, const datastructure::CamDistortion & distorsionParams) +{ + // set intrinsic parameters + m_intrinsic_parameters = intrinsicParams; + this->m_camMatrix.at(0, 0) = m_intrinsic_parameters(0, 0); + this->m_camMatrix.at(0, 1) = m_intrinsic_parameters(0, 1); + this->m_camMatrix.at(0, 2) = m_intrinsic_parameters(0, 2); + this->m_camMatrix.at(1, 0) = m_intrinsic_parameters(1, 0); + this->m_camMatrix.at(1, 1) = m_intrinsic_parameters(1, 1); + this->m_camMatrix.at(1, 2) = m_intrinsic_parameters(1, 2); + this->m_camMatrix.at(2, 0) = m_intrinsic_parameters(2, 0); + this->m_camMatrix.at(2, 1) = m_intrinsic_parameters(2, 1); + this->m_camMatrix.at(2, 2) = m_intrinsic_parameters(2, 2); + // set distortion parameters + m_distortion_parameters = distorsionParams; + this->m_camDistortion.at(0, 0) = m_distortion_parameters(0); + this->m_camDistortion.at(1, 0) = m_distortion_parameters(1); + this->m_camDistortion.at(2, 0) = m_distortion_parameters(2); + this->m_camDistortion.at(3, 0) = m_distortion_parameters(3); + this->m_camDistortion.at(4, 0) = m_distortion_parameters(4); +} } } From c3957925f7f3f0fcb15822ea7948c7150bc1d3b7 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Fri, 8 Jan 2021 10:48:38 +0100 Subject: [PATCH 03/21] Add test feature matching stabilization --- ...uleOpenCV_FeatureMatchingStabilization.pro | 74 ++++++++++ ...enCV_FeatureMatchingStabilization_conf.xml | 120 ++++++++++++++++ .../findremakenrules.pri | 43 ++++++ .../main.cpp | 129 ++++++++++++++++++ .../packagedependencies.txt | 1 + 5 files changed, 367 insertions(+) create mode 100644 tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro create mode 100644 tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml create mode 100644 tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/findremakenrules.pri create mode 100644 tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp create mode 100644 tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro new file mode 100644 index 00000000..905d7c87 --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro @@ -0,0 +1,74 @@ +## remove Qt dependencies +QT -= core gui +CONFIG -= qt + +## global defintions : target lib name, version +TARGET = SolARTest_ModuleOpenCV_FeatureMatchingStabilization +VERSION=0.9.0 + +DEFINES += MYVERSION=$${VERSION} +CONFIG += c++1z +CONFIG += console + +include(findremakenrules.pri) + +CONFIG(debug,debug|release) { + TARGETDEPLOYDIR = $${PWD}/../bin/Debug + DEFINES += _DEBUG=1 + DEFINES += DEBUG=1 +} + +CONFIG(release,debug|release) { + TARGETDEPLOYDIR = $${PWD}/../bin/Release + DEFINES += _NDEBUG=1 + DEFINES += NDEBUG=1 +} + +DEPENDENCIESCONFIG = sharedlib install_recurse + +win32:CONFIG -= static +win32:CONFIG += shared + +## Configuration for Visual Studio to install binaries and dependencies. Work also for QT Creator by replacing QMAKE_INSTALL +PROJECTCONFIG = QTVS + +#NOTE : CONFIG as staticlib or sharedlib, DEPENDENCIESCONFIG as staticlib or sharedlib, QMAKE_TARGET.arch and PROJECTDEPLOYDIR MUST BE DEFINED BEFORE templatelibconfig.pri inclusion +include ($$shell_quote($$shell_path($${QMAKE_REMAKEN_RULES_ROOT}/templateappconfig.pri))) # Shell_quote & shell_path required for visual on windows + +#DEFINES += BOOST_ALL_NO_LIB +DEFINES += BOOST_ALL_DYN_LINK +DEFINES += BOOST_AUTO_LINK_NOMANGLE +DEFINES += BOOST_LOG_DYN_LINK + +SOURCES += \ + main.cpp + +unix { + LIBS += -ldl + QMAKE_CXXFLAGS += -DBOOST_ALL_DYN_LINK +} + +macx { + QMAKE_MAC_SDK= macosx + QMAKE_CXXFLAGS += -fasm-blocks -x objective-c++ +} + +win32 { + QMAKE_LFLAGS += /MACHINE:X64 + DEFINES += WIN64 UNICODE _UNICODE + QMAKE_COMPILER_DEFINES += _WIN64 + + # Windows Kit (msvc2013 64) + LIBS += -L$$(WINDOWSSDKDIR)lib/winv6.3/um/x64 -lshell32 -lgdi32 -lComdlg32 + INCLUDEPATH += $$(WINDOWSSDKDIR)lib/winv6.3/um/x64 +} + +configfile.path = $${TARGETDEPLOYDIR}/ +configfile.files = $${PWD}/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml +INSTALLS += configfile + +DISTFILES += \ + packagedependencies.txt + +#NOTE : Must be placed at the end of the .pro +include ($$shell_quote($$shell_path($${QMAKE_REMAKEN_RULES_ROOT}/remaken_install_target.pri)))) # Shell_quote & shell_path required for visual on windows diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml new file mode 100644 index 00000000..a70053c4 --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 255 + + + + + + + + 0 + 255 + 0 + + + + + + + + + + diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/findremakenrules.pri b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/findremakenrules.pri new file mode 100644 index 00000000..3a13c891 --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/findremakenrules.pri @@ -0,0 +1,43 @@ +# Author(s) : Loic Touraine, Stephane Leduc + +android { + # unix path + USERHOMEFOLDER = $$clean_path($$(HOME)) + isEmpty(USERHOMEFOLDER) { + # windows path + USERHOMEFOLDER = $$clean_path($$(USERPROFILE)) + isEmpty(USERHOMEFOLDER) { + USERHOMEFOLDER = $$clean_path($$(HOMEDRIVE)$$(HOMEPATH)) + } + } +} + +unix:!android { + USERHOMEFOLDER = $$clean_path($$(HOME)) +} + +win32 { + USERHOMEFOLDER = $$clean_path($$(USERPROFILE)) + isEmpty(USERHOMEFOLDER) { + USERHOMEFOLDER = $$clean_path($$(HOMEDRIVE)$$(HOMEPATH)) + } +} + +exists(builddefs/qmake) { + QMAKE_REMAKEN_RULES_ROOT=builddefs/qmake +} +else { + QMAKE_REMAKEN_RULES_ROOT = $$clean_path($$(REMAKEN_RULES_ROOT)) + !isEmpty(QMAKE_REMAKEN_RULES_ROOT) { + QMAKE_REMAKEN_RULES_ROOT = $$clean_path($$(REMAKEN_RULES_ROOT)/qmake) + } + else { + QMAKE_REMAKEN_RULES_ROOT=$${USERHOMEFOLDER}/.remaken/rules/qmake + } +} + +!exists($${QMAKE_REMAKEN_RULES_ROOT}) { + error("Unable to locate remaken rules in " $${QMAKE_REMAKEN_RULES_ROOT} ". Either check your remaken installation, or provide the path to your remaken qmake root folder rules in REMAKEN_RULES_ROOT environment variable.") +} + +message("Remaken qmake build rules used : " $$QMAKE_REMAKEN_RULES_ROOT) \ No newline at end of file diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp new file mode 100644 index 00000000..5a9f52ce --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp @@ -0,0 +1,129 @@ +/** + * @copyright Copyright (c) 2017 B-com http://www.b-com.com/ + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "xpcf/xpcf.h" + +#include "api/input/devices/ICamera.h" +#include "api/features/IKeypointDetector.h" +#include "api/display/IImageViewer.h" +#include "api/display/IMatchesOverlay.h" +#include "api/display/I2DOverlay.h" +#include "api/features/IDescriptorMatcher.h" +#include "api/features/IDescriptorsExtractor.h" +#include "api/features/IMatchesFilter.h" +#include "core/Log.h" + +#include +#include +#include +#include + +using namespace SolAR; +using namespace SolAR::datastructure; +using namespace SolAR::api; + +namespace xpcf = org::bcom::xpcf; + +int main(int argc,char** argv) +{ +#if NDEBUG + boost::log::core::get()->set_logging_enabled(false); +#endif + + LOG_ADD_LOG_TO_CONSOLE(); + + /* instantiate component manager*/ + /* this is needed in dynamic mode */ + SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); + + if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml")!=org::bcom::xpcf::_SUCCESS) + { + LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml") + return -1; + } + + // declare and create components + LOG_INFO("Start creating components"); + auto camera = xpcfComponentManager->resolve(); + auto detector = xpcfComponentManager->resolve(); + auto extractor = xpcfComponentManager->resolve(); + auto matcher = xpcfComponentManager->resolve(); + auto matchesFilter = xpcfComponentManager->resolve(); + auto overlayMatches = xpcfComponentManager->resolve(); + auto overlay2D = xpcfComponentManager->resolve(); + auto viewer = xpcfComponentManager->resolve(); + LOG_INFO("All components created!"); + + // Open camera + if (camera->start() != FrameworkReturnCode::_SUCCESS) { + LOG_ERROR("Camera cannot start"); + return -1; + } + + // check feature matching stabilization + SRef frame1; + bool bInitFirstFrame(false); + for (;;) { + SRef image, imageDisplay; + if (camera->getNextImage(image) != FrameworkReturnCode::_SUCCESS) { + LOG_INFO("Error load image"); + return 0; + } + imageDisplay = image->copy(); + + std::vector keypoints; + SRef descriptors; + std::vector matches; + // feature detection + detector->detect(image, keypoints); + // feature extraction + extractor->extract(image, keypoints, descriptors); + // make a frame + SRef frame = xpcf::utils::make_shared(keypoints, descriptors, image); + + if (!bInitFirstFrame) { + LOG_INFO("Number of keypoints of the first frame: {}", keypoints.size()); + frame1 = frame; + bInitFirstFrame = true; + continue; + } + LOG_INFO("Number of keypoints: {}", keypoints.size()); + // feature matching + matcher->match(frame1->getDescriptors(), descriptors, matches); + LOG_INFO("Number of matches: {}", matches.size()); + // matches filter + matchesFilter->filter(matches, matches, frame1->getKeypoints(), keypoints); + LOG_INFO("Number of filtered matches: {}\n", matches.size()); + if (matches.size() < 200) { + frame1 = frame; + continue; + } + // draw keypoints and matches + overlayMatches->draw(image, imageDisplay, frame1->getKeypoints(), keypoints, matches); + overlay2D->drawCircles(keypoints, imageDisplay); + + // display + if (viewer->display(imageDisplay) == FrameworkReturnCode::_STOP) + break; + } + + return 0; +} + + + + + diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt new file mode 100644 index 00000000..002fcccc --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt @@ -0,0 +1 @@ +SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download From a37a088d979718e7f02d4e17eedb726da6f1f7bc Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Thu, 14 Jan 2021 15:00:49 +0100 Subject: [PATCH 04/21] Fix matchInRegion --- interfaces/SolARDescriptorMatcherKNNOpencv.h | 34 +- src/SolARDescriptorMatcherKNNOpencv.cpp | 458 ++++++++++-------- .../main.cpp | 7 +- 3 files changed, 293 insertions(+), 206 deletions(-) diff --git a/interfaces/SolARDescriptorMatcherKNNOpencv.h b/interfaces/SolARDescriptorMatcherKNNOpencv.h index 0e7d398d..40c55ac0 100644 --- a/interfaces/SolARDescriptorMatcherKNNOpencv.h +++ b/interfaces/SolARDescriptorMatcherKNNOpencv.h @@ -57,15 +57,15 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom: /// [in] desc2: target descriptor. /// [out] matches: ensemble of detected matches, a pair of source/target indices. ///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed. - IDescriptorMatcher::RetCode match( + IDescriptorMatcher::RetCode match( const SRef desc1, const SRef desc2, std::vector & matches) override; - /// @brief Matches a descriptor desc1 with an ensemble of descriptors desc2 based on KNN search strategy. - /// [in] desc1: source descriptor. - /// [in] desc2: target descriptors. - /// [out] matches: ensemble of detected matches, a pair of source/target indices. - ///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed. + /// @brief Matches a descriptor desc1 with an ensemble of descriptors desc2 based on KNN search strategy. + /// [in] desc1: source descriptor. + /// [in] desc2: target descriptors. + /// [out] matches: ensemble of detected matches, a pair of source/target indices. + ///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed. IDescriptorMatcher::RetCode match( const SRef descriptors1, const std::vector> & descriptors2, @@ -77,7 +77,7 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom: /// @param[in] frame The frame contains descriptors to match. /// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors. /// @return DesciptorMatcher::DESCRIPTORS_MATCHER_OK if matching succeeds, DesciptorMatcher::DESCRIPTORS_DONT_MATCH if the types of descriptors are different, DesciptorMatcher::DESCRIPTOR_TYPE_UNDEFINED if one of the descriptors set is unknown, or DesciptorMatcher::DESCRIPTOR_EMPTY if one of the set is empty. - virtual IDescriptorMatcher::RetCode matchInRegion( + IDescriptorMatcher::RetCode matchInRegion( const std::vector & points2D, const std::vector> & descriptors, const SRef frame, @@ -86,6 +86,21 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom: const float matchingDistanceMax = 0.f ) override; + /// @brief Match each descriptor input with descriptors of a frame in a region. The searching space is a circle which is defined by a 2D center and a radius + /// @param[in] currentFrame the current frame. + /// @param[in] lastFrame the last frame. + /// @param[out] matches a vector of matches between two frames representing pairs of keypoint indices relatively. + /// @param[in] radius the radius of search region around each keypoint of the last frame. + /// @param[in] matchingDistanceMax the maximum distance to valid a match. + /// @return DesciptorMatcher::DESCRIPTORS_MATCHER_OK if matching succeeds, DesciptorMatcher::DESCRIPTORS_DONT_MATCH if the types of descriptors are different, DesciptorMatcher::DESCRIPTOR_TYPE_UNDEFINED if one of the descriptors set is unknown, or DesciptorMatcher::DESCRIPTOR_EMPTY if one of the set is empty. + IDescriptorMatcher::RetCode matchInRegion( + const SRef currentFrame, + const SRef lastFrame, + std::vector &matches, + const float radius = 0.f, + const float matchingDistanceMax = 0.f + ) override; + private: @@ -101,11 +116,6 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom: int m_id; cv::FlannBasedMatcher m_matcher; - IDescriptorMatcher::RetCode match( - SRef& descriptors1, - SRef& descriptors2, - std::vector>& matches,int nbOfMatches); - }; } diff --git a/src/SolARDescriptorMatcherKNNOpencv.cpp b/src/SolARDescriptorMatcherKNNOpencv.cpp index 598dbd59..dc394273 100644 --- a/src/SolARDescriptorMatcherKNNOpencv.cpp +++ b/src/SolARDescriptorMatcherKNNOpencv.cpp @@ -17,250 +17,326 @@ #include "SolARDescriptorMatcherKNNOpencv.h" #include "SolAROpenCVHelper.h" #include "core/Log.h" +#include "opencv2/flann/kdtree_single_index.h" +#include "opencv2/flann.hpp" namespace xpcf = org::bcom::xpcf; XPCF_DEFINE_FACTORY_CREATE_INSTANCE(SolAR::MODULES::OPENCV::SolARDescriptorMatcherKNNOpencv) namespace SolAR { - using namespace datastructure; - using namespace api::features; - namespace MODULES { - namespace OPENCV { - - SolARDescriptorMatcherKNNOpencv::SolARDescriptorMatcherKNNOpencv():ConfigurableBase(xpcf::toUUID()) - { - declareInterface(this); - declareProperty("distanceRatio", m_distanceRatio); - declareProperty("radius", m_radius); - declareProperty("matchingDistanceMax", m_matchingDistanceMax); - LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv constructor") +using namespace datastructure; +using namespace api::features; +namespace MODULES { +namespace OPENCV { + +SolARDescriptorMatcherKNNOpencv::SolARDescriptorMatcherKNNOpencv():ConfigurableBase(xpcf::toUUID()) +{ + declareInterface(this); + declareProperty("distanceRatio", m_distanceRatio); + declareProperty("radius", m_radius); + declareProperty("matchingDistanceMax", m_matchingDistanceMax); + LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv constructor") +} + +SolARDescriptorMatcherKNNOpencv::~SolARDescriptorMatcherKNNOpencv() +{ + LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv destructor") +} + +cvflann::KDTreeSingleIndex> initKDTree(const std::vector &keypoints) +{ + cv::Mat_ features(0, 2); + for (const auto &kp : keypoints) { + cv::Mat row = (cv::Mat_(1, 2) << kp.getX(), kp.getY()); + features.push_back(row); + } + cvflann::KDTreeSingleIndexParams indexParams; + cvflann::Matrix samplesMatrix((float*)features.data, features.rows, features.cols); + cvflann::KDTreeSingleIndex> kdtree(samplesMatrix, indexParams); + kdtree.buildIndex(); + return kdtree; +} + +int radiusSearch(cvflann::KDTreeSingleIndex>& kdtree, const Point2Df& query, const float & radius, std::vector & indices, std::vector & dists, const int & maxResults = 500) +{ + std::vector pt2D = { query.getX(), query.getY() }; + cvflann::Matrix queryMatrix(pt2D.data(), 1, 2); + cvflann::Matrix indicesMatrix(new int[maxResults], 1, maxResults); + cvflann::Matrix distsMatrix(new float[maxResults], 1, maxResults); + int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, radius * radius, cvflann::SearchParams()); + indices.assign(indicesMatrix.data, indicesMatrix.data + nbFound); + dists.assign(distsMatrix.data, distsMatrix.data + nbFound); + return nbFound; +} + +IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::match( + SRef desc1,SRef desc2, std::vector& matches){ + + matches.clear(); + + // check if the descriptors type match + if(desc1->getDescriptorType() != desc2->getDescriptorType()){ + return IDescriptorMatcher::RetCode::DESCRIPTORS_DONT_MATCH; } - SolARDescriptorMatcherKNNOpencv::~SolARDescriptorMatcherKNNOpencv() - { - LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv destructor") + if (desc1->getNbDescriptors() == 0 || desc2->getNbDescriptors() == 0){ + return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; } - - IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::match( - SRef desc1,SRef desc2, std::vector& matches){ - + if (desc1->getNbDescriptors()<2 || desc2->getNbDescriptors()<2) { matches.clear(); + return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; // not enough descriptors to use opencv::knnMatch + } - // check if the descriptors type match - if(desc1->getDescriptorType() != desc2->getDescriptorType()){ - return IDescriptorMatcher::RetCode::DESCRIPTORS_DONT_MATCH; - } - - if (desc1->getNbDescriptors() == 0 || desc2->getNbDescriptors() == 0){ - return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; - } - - if (desc1->getNbDescriptors()<2 || desc2->getNbDescriptors()<2) { - matches.clear(); - return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; // not enough descriptors to use opencv::knnMatch - } - - std::vector> initial_matches; - std::vector good_matches; + std::vector> initial_matches; + std::vector good_matches; - //since it is an openCV implementation we need to convert back the descriptors from SolAR to Opencv - uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(desc1->getDescriptorDataType()); + //since it is an openCV implementation we need to convert back the descriptors from SolAR to Opencv + uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(desc1->getDescriptorDataType()); - cv::Mat cvDescriptor1(desc1->getNbDescriptors(), desc1->getNbElements(), type_conversion); - cvDescriptor1.data=(uchar*)desc1->data(); + cv::Mat cvDescriptor1(desc1->getNbDescriptors(), desc1->getNbElements(), type_conversion); + cvDescriptor1.data=(uchar*)desc1->data(); - cv::Mat cvDescriptor2(desc2->getNbDescriptors(), desc1->getNbElements(), type_conversion); - cvDescriptor2.data=(uchar*)desc2->data(); + cv::Mat cvDescriptor2(desc2->getNbDescriptors(), desc1->getNbElements(), type_conversion); + cvDescriptor2.data=(uchar*)desc2->data(); - if (desc1->getDescriptorDataType() != DescriptorDataType::TYPE_32F) - cvDescriptor1.convertTo(cvDescriptor1, CV_32F); - if (desc2->getDescriptorDataType() != DescriptorDataType::TYPE_32F) - cvDescriptor2.convertTo(cvDescriptor2, CV_32F); + if (desc1->getDescriptorDataType() != DescriptorDataType::TYPE_32F) + cvDescriptor1.convertTo(cvDescriptor1, CV_32F); + if (desc2->getDescriptorDataType() != DescriptorDataType::TYPE_32F) + cvDescriptor2.convertTo(cvDescriptor2, CV_32F); - std::vector< std::vector > nn_matches; - m_matcher.knnMatch(cvDescriptor1, cvDescriptor2, nn_matches,2); - std::map> matches21; - for(unsigned i = 0; i < nn_matches.size(); i++) { - if(nn_matches[i][0].distance < m_distanceRatio * nn_matches[i][1].distance) { - matches21[nn_matches[i][0].trainIdx][nn_matches[i][0].queryIdx] = nn_matches[i][0].distance; - } + std::vector< std::vector > nn_matches; + m_matcher.knnMatch(cvDescriptor1, cvDescriptor2, nn_matches,2); + std::map> matches21; + for(unsigned i = 0; i < nn_matches.size(); i++) { + if(nn_matches[i][0].distance < m_distanceRatio * nn_matches[i][1].distance) { + matches21[nn_matches[i][0].trainIdx][nn_matches[i][0].queryIdx] = nn_matches[i][0].distance; } + } - // get best matches to descriptors 2 - for (auto it_des2 : matches21) { - uint32_t idxDes2 = it_des2.first; - std::map infoMatch = it_des2.second; - uint32_t bestIdxDes1; - float bestDistance = FLT_MAX; - for (auto it_des1: infoMatch) - if (it_des1.second < bestDistance) { - bestDistance = it_des1.second; - bestIdxDes1 = it_des1.first; - } - matches.push_back(DescriptorMatch(bestIdxDes1, idxDes2, bestDistance)); - } - - return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; + // get best matches to descriptors 2 + for (auto it_des2 : matches21) { + uint32_t idxDes2 = it_des2.first; + std::map infoMatch = it_des2.second; + uint32_t bestIdxDes1; + float bestDistance = FLT_MAX; + for (auto it_des1: infoMatch) + if (it_des1.second < bestDistance) { + bestDistance = it_des1.second; + bestIdxDes1 = it_des1.first; + } + matches.push_back(DescriptorMatch(bestIdxDes1, idxDes2, bestDistance)); + } - } + return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; - IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::match( - const SRef descriptors1, - const std::vector>& descriptors2, - std::vector& matches - ) - { +} - matches.clear(); +IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::match( + const SRef descriptors1, + const std::vector>& descriptors2, + std::vector& matches + ) +{ - if (descriptors1->getNbDescriptors() ==0 || descriptors2.size()== 0) - return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; + matches.clear(); - uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptors1->getDescriptorDataType()); + if (descriptors1->getNbDescriptors() ==0 || descriptors2.size()== 0) + return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; - cv::Mat cvDescriptors1(descriptors1->getNbDescriptors(), descriptors1->getNbElements(), type_conversion); - cvDescriptors1.data=(uchar*)descriptors1->data(); + uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptors1->getDescriptorDataType()); - if (descriptors1->getDescriptorDataType() != DescriptorDataType::TYPE_32F) - cvDescriptors1.convertTo(cvDescriptors1, CV_32F); + cv::Mat cvDescriptors1(descriptors1->getNbDescriptors(), descriptors1->getNbElements(), type_conversion); + cvDescriptors1.data=(uchar*)descriptors1->data(); - std::vector cvDescriptors; - for(unsigned k=0;kgetDescriptorDataType() != DescriptorDataType::TYPE_32F) + cvDescriptors1.convertTo(cvDescriptors1, CV_32F); - uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptors2[k]->getDescriptorDataType()); + std::vector cvDescriptors; + for(unsigned k=0;kgetNbDescriptors(), descriptors2[k]->getNbElements(), type_conversion); - cvDescriptor.data=(uchar*)(descriptors2[k]->data()); + uint32_t type_conversion= SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptors2[k]->getDescriptorDataType()); - if (descriptors2[k]->getDescriptorDataType() != DescriptorDataType::TYPE_32F) - cvDescriptor.convertTo(cvDescriptor, CV_32F); + cv::Mat cvDescriptor(descriptors2[k]->getNbDescriptors(), descriptors2[k]->getNbElements(), type_conversion); + cvDescriptor.data=(uchar*)(descriptors2[k]->data()); - cvDescriptors.push_back(cvDescriptor); - } + if (descriptors2[k]->getDescriptorDataType() != DescriptorDataType::TYPE_32F) + cvDescriptor.convertTo(cvDescriptor, CV_32F); + cvDescriptors.push_back(cvDescriptor); + } - cv::Mat cvDescriptors2; - cv::vconcat(cvDescriptors,cvDescriptors2); + cv::Mat cvDescriptors2; + cv::vconcat(cvDescriptors,cvDescriptors2); - int nbOfMatches=2; - if(cvDescriptors2.rows > nn_matches; - m_matcher.knnMatch(cvDescriptors1, cvDescriptors2, nn_matches,nbOfMatches); - std::map> matches21; - for(unsigned i = 0; i < nn_matches.size(); i++) { - if(nn_matches[i][0].distance < m_distanceRatio * nn_matches[i][1].distance) { - matches21[nn_matches[i][0].trainIdx][nn_matches[i][0].queryIdx] = nn_matches[i][0].distance; - } - } - // get best matches to descriptors 2 - for (auto it_des2 : matches21) { - uint32_t idxDes2 = it_des2.first; - std::map infoMatch = it_des2.second; - uint32_t bestIdxDes1; - float bestDistance = FLT_MAX; - for (auto it_des1 : infoMatch) - if (it_des1.second < bestDistance) { - bestDistance = it_des1.second; - bestIdxDes1 = it_des1.first; - } - matches.push_back(DescriptorMatch(bestIdxDes1, idxDes2, bestDistance)); - } + if(cvDescriptors2.rows > nn_matches; + m_matcher.knnMatch(cvDescriptors1, cvDescriptors2, nn_matches,nbOfMatches); + std::map> matches21; + for(unsigned i = 0; i < nn_matches.size(); i++) { + if(nn_matches[i][0].distance < m_distanceRatio * nn_matches[i][1].distance) { + matches21[nn_matches[i][0].trainIdx][nn_matches[i][0].queryIdx] = nn_matches[i][0].distance; + } } + // get best matches to descriptors 2 + for (auto it_des2 : matches21) { + uint32_t idxDes2 = it_des2.first; + std::map infoMatch = it_des2.second; + uint32_t bestIdxDes1; + float bestDistance = FLT_MAX; + for (auto it_des1 : infoMatch) + if (it_des1.second < bestDistance) { + bestDistance = it_des1.second; + bestIdxDes1 = it_des1.first; + } + matches.push_back(DescriptorMatch(bestIdxDes1, idxDes2, bestDistance)); + } + return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; - IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const std::vector& points2D, const std::vector>& descriptors, const SRef frame, std::vector& matches, const float radius, const float matchingDistanceMax) - { - matches.clear(); - float radiusValue = radius > 0 ? radius : m_radius; - float matchingDistanceMaxValue = matchingDistanceMax > 0 ? matchingDistanceMax : m_matchingDistanceMax; - SRef descriptorFrame = frame->getDescriptors(); +} - if (descriptors.size() == 0 || descriptorFrame->getNbDescriptors() == 0) - return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; +IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const std::vector& points2D, const std::vector>& descriptors, const SRef frame, std::vector& matches, const float radius, const float matchingDistanceMax) +{ + matches.clear(); + float radiusValue = radius > 0 ? radius : m_radius; + float matchingDistanceMaxValue = matchingDistanceMax > 0 ? matchingDistanceMax : m_matchingDistanceMax; + SRef descriptorFrame = frame->getDescriptors(); - // check if the descriptors type match - if (descriptorFrame->getDescriptorType() != descriptors[0]->getDescriptorType()) { - return IDescriptorMatcher::RetCode::DESCRIPTORS_DONT_MATCH; - } + if (descriptors.size() == 0 || descriptorFrame->getNbDescriptors() == 0) + return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; - if (points2D.size() != descriptors.size()) { - return IDescriptorMatcher::RetCode::DESCRIPTOR_TYPE_UNDEFINED; - } + // check if the descriptors type match + if (descriptorFrame->getDescriptorType() != descriptors[0]->getDescriptorType()) { + return IDescriptorMatcher::RetCode::DESCRIPTORS_DONT_MATCH; + } - uint32_t type_conversion = SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptorFrame->getDescriptorDataType()); + if (points2D.size() != descriptors.size()) { + return IDescriptorMatcher::RetCode::DESCRIPTOR_TYPE_UNDEFINED; + } - // convert frame descriptor to opencv's descriptor - cv::Mat cvDescriptorFrame(descriptorFrame->getNbDescriptors(), descriptorFrame->getNbElements(), type_conversion); - cvDescriptorFrame.data = (uchar*)descriptorFrame->data(); + uint32_t type_conversion = SolAROpenCVHelper::deduceOpenDescriptorCVType(descriptorFrame->getDescriptorDataType()); - std::vector cvDescriptors; - for (unsigned k = 0; k < descriptors.size(); k++) { - cv::Mat cvDescriptor(descriptors[k]->getNbDescriptors(), descriptors[k]->getNbElements(), type_conversion); - cvDescriptor.data = (uchar*)(descriptors[k]->data()); - cvDescriptors.push_back(cvDescriptor); - } + // convert frame descriptor to opencv's descriptor + cv::Mat cvDescriptorFrame(descriptorFrame->getNbDescriptors(), descriptorFrame->getNbElements(), type_conversion); + cvDescriptorFrame.data = (uchar*)descriptorFrame->data(); - // init kd tree to accelerate searching - const std::vector &keypointsFrame = frame->getKeypoints(); - std::vector pointsForSearch; - for (auto &it : keypointsFrame) - pointsForSearch.push_back(cv::Point2f(it.getX(), it.getY())); - - cv::flann::KDTreeIndexParams indexParams; - cv::flann::Index kdtree(cv::Mat(pointsForSearch).reshape(1), indexParams); - - int imgWidth = frame->getView()->getWidth(); - int imgHeight = frame->getView()->getHeight(); - - // Match each descriptor to descriptors of frame in a corresponding region - std::vector checkMatches(keypointsFrame.size(), true); - int idx = 0; - for (const auto &it : cvDescriptors) { - std::vector idxCandidates; - if ((points2D[idx].getX() > 0) && (points2D[idx].getX() < imgWidth) && (points2D[idx].getY() > 0) && (points2D[idx].getY() < imgHeight)) { - std::vector dists; - std::vector query = { points2D[idx].getX(), points2D[idx].getY() }; - kdtree.radiusSearch(query, idxCandidates, dists, radiusValue, 30); - } + std::vector cvDescriptors; + for (unsigned k = 0; k < descriptors.size(); k++) { + cv::Mat cvDescriptor(descriptors[k]->getNbDescriptors(), descriptors[k]->getNbElements(), type_conversion); + cvDescriptor.data = (uchar*)(descriptors[k]->data()); + cvDescriptors.push_back(cvDescriptor); + } - if (idxCandidates.size() > 0) { - float bestDist = std::numeric_limits::max(); - float bestDist2 = std::numeric_limits::max(); - int bestIdx = -1; - for (auto &it_des: idxCandidates) { - if (it_des == 0) - continue; - float dist = cv::norm(it, cvDescriptorFrame.row(it_des), cv::NORM_L2); - if (dist < bestDist) - { - bestDist2 = bestDist; - bestDist = dist; - bestIdx = it_des; - } - else if (dist < bestDist2) - { - bestDist2 = dist; - } + // init kd tree to accelerate searching + const std::vector &keypointsFrame = frame->getKeypoints(); + auto kdtree = initKDTree(keypointsFrame); + + // Match each descriptor to descriptors of frame in a corresponding region + std::vector checkMatches(keypointsFrame.size(), true); + int idx = 0; + for (const auto &it : cvDescriptors) { + std::vector idxCandidates; + std::vector dists; + Point2Df query(points2D[idx].getX(), points2D[idx].getY()); + int nbFound = radiusSearch(kdtree, query, radiusValue, idxCandidates, dists, keypointsFrame.size()); + if (nbFound > 0) { + float bestDist = std::numeric_limits::max(); + float bestDist2 = std::numeric_limits::max(); + int bestIdx = -1; + for (const auto &it_des: idxCandidates) { + float dist = cv::norm(it, cvDescriptorFrame.row(it_des), cv::NORM_L2); + if (dist < bestDist) + { + bestDist2 = bestDist; + bestDist = dist; + bestIdx = it_des; } - if ((bestIdx != -1) && (bestDist < matchingDistanceMaxValue) && (bestDist < m_distanceRatio * bestDist2) && (checkMatches[bestIdx])) { - matches.push_back(DescriptorMatch(idx, bestIdx, bestDist)); - checkMatches[bestIdx] = false; + else if (dist < bestDist2) + { + bestDist2 = dist; } } + if ((bestIdx != -1) && (bestDist < matchingDistanceMaxValue) && (bestDist < m_distanceRatio * bestDist2) && (checkMatches[bestIdx])) { + matches.push_back(DescriptorMatch(idx, bestIdx, bestDist)); + checkMatches[bestIdx] = false; + } + } + idx++; + } + + return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; +} + +IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const SRef currentFrame, const SRef lastFrame, std::vector& matches, const float radius, const float matchingDistanceMax) +{ + matches.clear(); + float radiusValue = radius > 0 ? radius : m_radius; + float matchingDistanceMaxValue = matchingDistanceMax > 0 ? matchingDistanceMax : m_matchingDistanceMax; + SRef desCurrentFrame = currentFrame->getDescriptors(); + SRef desLastFrame = lastFrame->getDescriptors(); + if ((desCurrentFrame->getNbDescriptors() == 0) || (desLastFrame->getNbDescriptors() == 0)) + return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; + + // check if the descriptors type match + if (desCurrentFrame->getDescriptorType() != desLastFrame->getDescriptorType()) { + return IDescriptorMatcher::RetCode::DESCRIPTORS_DONT_MATCH; + } - idx++; - } - - return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; + uint32_t type_conversion = SolAROpenCVHelper::deduceOpenDescriptorCVType(desCurrentFrame->getDescriptorDataType()); + + // convert frame descriptor to opencv's descriptor + cv::Mat cvDesCurrentFrame(desCurrentFrame->getNbDescriptors(), desCurrentFrame->getNbElements(), type_conversion); + cvDesCurrentFrame.data = (uchar*)desCurrentFrame->data(); + + cv::Mat cvDesLastFrame(desLastFrame->getNbDescriptors(), desLastFrame->getNbElements(), type_conversion); + cvDesLastFrame.data = (uchar*)desLastFrame->data(); + + // init kd tree to accelerate searching + const std::vector &keypointsLastFrame = lastFrame->getKeypoints(); + auto kdtree = initKDTree(keypointsLastFrame); + + // Match each descriptor of the current frame to descriptors of the last frame in a corresponding region + std::vector checkMatches(keypointsLastFrame.size(), true); + const std::vector &keypointsCurrentFrame = currentFrame->getKeypoints(); + for (int i = 0; i < keypointsCurrentFrame.size(); ++i) { + std::vector idxCandidates; + std::vector dists; + Point2Df queryPt2D(keypointsCurrentFrame[i].getX(), keypointsCurrentFrame[i].getY()); + cv::Mat queryDes = cvDesCurrentFrame.row(i); + int nbFound = radiusSearch(kdtree, queryPt2D, radiusValue, idxCandidates, dists, keypointsLastFrame.size()); + if (nbFound > 0) { + float bestDist = std::numeric_limits::max(); + float bestDist2 = std::numeric_limits::max(); + int bestIdx = -1; + for (const auto &idx_des: idxCandidates) { + float dist = cv::norm(queryDes, cvDesLastFrame.row(idx_des), cv::NORM_L2); + if (dist < bestDist) + { + bestDist2 = bestDist; + bestDist = dist; + bestIdx = idx_des; + } + else if (dist < bestDist2) + { + bestDist2 = dist; + } + } + if ((bestIdx != -1) && (bestDist < matchingDistanceMaxValue) && (bestDist < m_distanceRatio * bestDist2) && (checkMatches[bestIdx])) { + matches.push_back(DescriptorMatch(i, bestIdx, bestDist)); + checkMatches[bestIdx] = false; + } + } } + return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK; +} - } - } +} +} } // end of namespace SolAR diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp index 5a9f52ce..fd18ed19 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp @@ -102,17 +102,18 @@ int main(int argc,char** argv) } LOG_INFO("Number of keypoints: {}", keypoints.size()); // feature matching - matcher->match(frame1->getDescriptors(), descriptors, matches); + //matcher->match(descriptors, frame1->getDescriptors(), matches); + matcher->matchInRegion(frame, frame1, matches); LOG_INFO("Number of matches: {}", matches.size()); // matches filter - matchesFilter->filter(matches, matches, frame1->getKeypoints(), keypoints); + matchesFilter->filter(matches, matches, keypoints, frame1->getKeypoints()); LOG_INFO("Number of filtered matches: {}\n", matches.size()); if (matches.size() < 200) { frame1 = frame; continue; } // draw keypoints and matches - overlayMatches->draw(image, imageDisplay, frame1->getKeypoints(), keypoints, matches); + overlayMatches->draw(image, imageDisplay, keypoints, frame1->getKeypoints(), matches); overlay2D->drawCircles(keypoints, imageDisplay); // display From 139f58277d23ecefb06e7679be229f776c5dc19e Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Tue, 26 Jan 2021 10:07:19 +0100 Subject: [PATCH 05/21] Move to 0.9.1 --- SolARModuleOpenCV.pro | 2 +- bcom-SolARModuleOpenCV.pc.in | 2 +- packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_CameraCalibration.pro | 2 +- .../packagedependencies.txt | 4 ++-- .../SolARTest_ModuleOpenCV_DescriptorMatcher.pro | 2 +- .../SolARTest_ModuleOpenCV_DescriptorMatcher_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_DeviceDataLoader.pro | 2 +- .../SolARTest_ModuleOpenCV_DeviceDataLoader_conf.xml | 4 ++-- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration.pro | 2 +- ...ARTest_ModuleOpenCV_DeviceDualMarkerCalibration_conf.xml | 6 +++--- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_DevicePoseCorrection.pro | 2 +- .../SolARTest_ModuleOpenCV_DevicePoseCorrection_conf.xml | 6 +++--- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro | 2 +- ...RTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_FiducialMarker.pro | 2 +- .../SolARTest_ModuleOpenCV_FiducialMarker_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer.pro | 2 +- ...ARTest_ModuleOpenCV_FundamentalMatrixDecomposer_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_FundamentalMatrixEstimation.pro | 2 +- ...ARTest_ModuleOpenCV_FundamentalMatrixEstimation_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_ImageConvertor.pro | 2 +- .../SolARTest_ModuleOpenCV_ImageConvertor_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_ImageLoader.pro | 2 +- .../SolARTest_ModuleOpenCV_ImageLoader_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_MatchesFilter.pro | 2 +- .../SolARTest_ModuleOpenCV_MatchesFilter_conf.xml | 2 +- .../packagedependencies.txt | 2 +- .../SolARTest_ModuleOpenCV_OpticalFlow.pro | 2 +- .../SolARTest_ModuleOpenCV_OpticalFlow_conf.xml | 2 +- .../packagedependencies.txt | 2 +- tests/packagedependencies-linux.txt | 2 +- tests/packagedependencies-win.txt | 2 +- tests/packagedependencies.txt | 6 +++--- xpcf_SolARModuleOpenCV_registry.xml | 2 +- 45 files changed, 53 insertions(+), 53 deletions(-) diff --git a/SolARModuleOpenCV.pro b/SolARModuleOpenCV.pro index 080c2d5b..5c813900 100644 --- a/SolARModuleOpenCV.pro +++ b/SolARModuleOpenCV.pro @@ -6,7 +6,7 @@ CONFIG -= qt INSTALLSUBDIR = SolARBuild TARGET = SolARModuleOpenCV FRAMEWORK = $$TARGET -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} DEFINES += TEMPLATE_LIBRARY diff --git a/bcom-SolARModuleOpenCV.pc.in b/bcom-SolARModuleOpenCV.pc.in index ed391af4..2209b2c1 100644 --- a/bcom-SolARModuleOpenCV.pc.in +++ b/bcom-SolARModuleOpenCV.pc.in @@ -5,7 +5,7 @@ libdir=${exec_prefix}/lib includedir=${prefix}/interfaces Name: SolARModuleOpenCV Description: -Version: 0.9.0 +Version: 0.9.1 Requires: Libs: -L${libdir} -l${libname} Libs.private: ${libdir}/${pfx}${libname}.${lext} diff --git a/packagedependencies.txt b/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/packagedependencies.txt +++ b/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro index fb637e1f..5636ae7a 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_CameraCalibration -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_CameraCalibration/packagedependencies.txt index 09399544..920d5cdd 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/packagedependencies.txt @@ -1,2 +1,2 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download -SolARModuleOpenCV|0.9.0|SolARModuleOpenCV|SolARBuild@github|https://github.com/SolarFramework/SolARModuleOpenCV/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARModuleOpenCV|0.9.1|SolARModuleOpenCV|SolARBuild@github|https://github.com/SolarFramework/SolARModuleOpenCV/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher.pro b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher.pro index 6c01348d..18e9c7fd 100644 --- a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher.pro +++ b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_DescriptorMatcher -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher_conf.xml b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher_conf.xml index 105ad66d..cf431ecd 100644 --- a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/SolARTest_ModuleOpenCV_DescriptorMatcher_conf.xml @@ -1,7 +1,7 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader.pro b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader.pro index f046b579..26a24e94 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader.pro +++ b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_DeviceDataLoader -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader_conf.xml b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader_conf.xml index 4639d05f..60d23539 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/SolARTest_ModuleOpenCV_DeviceDataLoader_conf.xml @@ -1,6 +1,6 @@ - + @@ -15,7 +15,7 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_DeviceDataLoader/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration.pro b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration.pro index 5e17394f..7a4e1553 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration.pro +++ b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration_conf.xml b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration_conf.xml index ad501b88..f7a69bdf 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration_conf.xml @@ -1,6 +1,6 @@ - + @@ -53,14 +53,14 @@ - + - + diff --git a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_DeviceDualMarkerCalibration/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection.pro b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection.pro index 4e7a9f6e..98d94804 100644 --- a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection.pro +++ b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_DevicePoseCorrection -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection_conf.xml b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection_conf.xml index e3cd05be..f832e81f 100644 --- a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/SolARTest_ModuleOpenCV_DevicePoseCorrection_conf.xml @@ -1,6 +1,6 @@ - + @@ -53,14 +53,14 @@ - + - + diff --git a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_DevicePoseCorrection/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro index 905d7c87..46d413d5 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_FeatureMatchingStabilization -VERSION=0.9.0 +VERSION=[2~[3~[5~0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml index a70053c4..9782399d 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker.pro b/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker.pro index 880b958f..a591ce1f 100644 --- a/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker.pro +++ b/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_FiducialMarker -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker_conf.xml b/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker_conf.xml index 2c56f6fd..3143cd69 100644 --- a/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_FiducialMarker/SolARTest_ModuleOpenCV_FiducialMarker_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_FiducialMarker/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_FiducialMarker/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_FiducialMarker/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_FiducialMarker/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer.pro b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer.pro index 313cdeeb..48921fea 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer.pro +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer_conf.xml b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer_conf.xml index 8e1778a3..0c445645 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixDecomposer/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation.pro b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation.pro index b2e567b0..6d5bebe7 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation.pro +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_FundamentalMatrixEstimation -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation_conf.xml b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation_conf.xml index a6622512..da9cb59a 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_FundamentalMatrixEstimation/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor.pro b/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor.pro index dc01c9d9..ea61b9f9 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor.pro +++ b/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_ImageConvertor -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor_conf.xml b/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor_conf.xml index fe4fb11c..6c193434 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_ImageConvertor/SolARTest_ModuleOpenCV_ImageConvertor_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_ImageConvertor/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_ImageConvertor/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageConvertor/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_ImageConvertor/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader.pro b/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader.pro index 5df249a5..c10c5c1e 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader.pro +++ b/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_ImageLoader -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader_conf.xml b/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader_conf.xml index 3e6d2d0b..1f7e41f5 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_ImageLoader/SolARTest_ModuleOpenCV_ImageLoader_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_ImageLoader/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_ImageLoader/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_ImageLoader/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_ImageLoader/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter.pro b/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter.pro index 6a43453a..00f5d77c 100644 --- a/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter.pro +++ b/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_MatchesFilter -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter_conf.xml b/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter_conf.xml index 2b3b2d83..d0944d8e 100644 --- a/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_MatchesFilter/SolARTest_ModuleOpenCV_MatchesFilter_conf.xml @@ -1,6 +1,6 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_MatchesFilter/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_MatchesFilter/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_MatchesFilter/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_MatchesFilter/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow.pro b/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow.pro index 04abda59..4451a459 100644 --- a/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow.pro +++ b/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_OpticalFlow -VERSION=0.9.0 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow_conf.xml b/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow_conf.xml index c844502c..63559bc3 100644 --- a/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow_conf.xml +++ b/tests/SolARTest_ModuleOpenCV_OpticalFlow/SolARTest_ModuleOpenCV_OpticalFlow_conf.xml @@ -1,7 +1,7 @@ - + diff --git a/tests/SolARTest_ModuleOpenCV_OpticalFlow/packagedependencies.txt b/tests/SolARTest_ModuleOpenCV_OpticalFlow/packagedependencies.txt index 002fcccc..b9b3f9a5 100644 --- a/tests/SolARTest_ModuleOpenCV_OpticalFlow/packagedependencies.txt +++ b/tests/SolARTest_ModuleOpenCV_OpticalFlow/packagedependencies.txt @@ -1 +1 @@ -SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download +SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download diff --git a/tests/packagedependencies-linux.txt b/tests/packagedependencies-linux.txt index 671a0ff5..c4fcf416 100644 --- a/tests/packagedependencies-linux.txt +++ b/tests/packagedependencies-linux.txt @@ -1 +1 @@ -SolARModuleOpenGL|0.9.0|SolARModuleOpenGL|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenGL/releases/download +SolARModuleOpenGL|0.9.1|SolARModuleOpenGL|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenGL/releases/download diff --git a/tests/packagedependencies-win.txt b/tests/packagedependencies-win.txt index eb59af24..1da21185 100644 --- a/tests/packagedependencies-win.txt +++ b/tests/packagedependencies-win.txt @@ -1,2 +1,2 @@ -SolARModuleOpenGL|0.9.0|SolARModuleOpenGL|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenGL/releases/download +SolARModuleOpenGL|0.9.1|SolARModuleOpenGL|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenGL/releases/download diff --git a/tests/packagedependencies.txt b/tests/packagedependencies.txt index c2f3750b..46886bfa 100644 --- a/tests/packagedependencies.txt +++ b/tests/packagedependencies.txt @@ -1,3 +1,3 @@ -SolARModuleOpenCV|0.9.0|SolARModuleOpenCV|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenCV/releases/download -SolARModuleFBOW|0.9.0|SolARModuleFBOW|SolARBuild@github|https://github.com/SolarFramework/SolARModuleFBOW/releases/download -SolARModuleTools|0.9.0|SolARModuleTools|SolARBuild@github|https://github.com/SolarFramework/SolARModuleTools/releases/download +SolARModuleOpenCV|0.9.1|SolARModuleOpenCV|SolARBuild@github|https://github.com/SolarFramework/SolarModuleOpenCV/releases/download +SolARModuleFBOW|0.9.1|SolARModuleFBOW|SolARBuild@github|https://github.com/SolarFramework/SolARModuleFBOW/releases/download +SolARModuleTools|0.9.1|SolARModuleTools|SolARBuild@github|https://github.com/SolarFramework/SolARModuleTools/releases/download diff --git a/xpcf_SolARModuleOpenCV_registry.xml b/xpcf_SolARModuleOpenCV_registry.xml index 0f8af74d..b502ebcd 100644 --- a/xpcf_SolARModuleOpenCV_registry.xml +++ b/xpcf_SolARModuleOpenCV_registry.xml @@ -1,6 +1,6 @@ - + From c10afc41a0b4070c2906d84e38972330dc8eee2a Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Tue, 26 Jan 2021 18:33:49 +0100 Subject: [PATCH 06/21] Fix test feature matching stabilization after merging --- .../SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro | 2 +- .../main.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro index 46d413d5..ff9bac11 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/SolARTest_ModuleOpenCV_FeatureMatchingStabilization.pro @@ -4,7 +4,7 @@ CONFIG -= qt ## global defintions : target lib name, version TARGET = SolARTest_ModuleOpenCV_FeatureMatchingStabilization -VERSION=[2~[3~[5~0.9.1 +VERSION=0.9.1 DEFINES += MYVERSION=$${VERSION} CONFIG += c++1z diff --git a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp index fd18ed19..d93476c7 100644 --- a/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp +++ b/tests/SolARTest_ModuleOpenCV_FeatureMatchingStabilization/main.cpp @@ -108,7 +108,7 @@ int main(int argc,char** argv) // matches filter matchesFilter->filter(matches, matches, keypoints, frame1->getKeypoints()); LOG_INFO("Number of filtered matches: {}\n", matches.size()); - if (matches.size() < 200) { + if (matches.size() < 600) { frame1 = frame; continue; } From 2ee5310132001051237a02490738e066dcef09e7 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Fri, 5 Feb 2021 16:50:06 +0100 Subject: [PATCH 07/21] fix: radius search in map fusion using flann --- src/SolARMapFusionOpencv.cpp | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/src/SolARMapFusionOpencv.cpp b/src/SolARMapFusionOpencv.cpp index c9a6f7ec..ea30b2f5 100644 --- a/src/SolARMapFusionOpencv.cpp +++ b/src/SolARMapFusionOpencv.cpp @@ -17,6 +17,8 @@ #include "SolARMapFusionOpencv.h" #include "SolAROpenCVHelper.h" #include "core/Log.h" +#include "opencv2/flann/kdtree_single_index.h" +#include "opencv2/flann.hpp" namespace xpcf = org::bcom::xpcf; @@ -70,11 +72,15 @@ FrameworkReturnCode SolARMapFusionOpencv::merge(SRef map, SRef globalPointcloudManager->getAllPoints(globalCloudPoints); globalKeyframeMananger->getAllKeyframes(globalKeyframes); // init kd tree of global point cloud - std::vector pointsForSearch; - for (auto &cp : globalCloudPoints) - pointsForSearch.push_back(cv::Point3f(cp->getX(), cp->getY(), cp->getZ())); - cv::flann::KDTreeIndexParams indexParams; - cv::flann::Index kdtree(cv::Mat(pointsForSearch).reshape(1), indexParams); + cv::Mat_ features(0, 3); + for (const auto &cp : globalCloudPoints) { + cv::Mat row = (cv::Mat_(1, 3) << cp->getX(), cp->getY(), cp->getZ()); + features.push_back(row); + } + cvflann::KDTreeSingleIndexParams indexParams; + cvflann::Matrix samplesMatrix((float*)features.data, features.rows, features.cols); + cvflann::KDTreeSingleIndex> kdtree(samplesMatrix, indexParams); + kdtree.buildIndex(); // find correspondences for each point std::vector < std::pair, SRef>> duplicatedCPs; // first is local CP, second is global CP std::vector checkMatches(globalCloudPoints.size(), true); @@ -82,12 +88,17 @@ FrameworkReturnCode SolARMapFusionOpencv::merge(SRef map, SRef // find point by 3D distance std::vector idxCandidates; std::vector dists; - std::vector query = { cp->getX(), cp->getY(), cp->getZ() }; - kdtree.radiusSearch(query, idxCandidates, dists, m_radius, 30); + std::vector pt3D = { cp->getX(), cp->getY(), cp->getZ() }; + cvflann::Matrix queryMatrix(pt3D.data(), 1, 3); + cvflann::Matrix indicesMatrix(new int[globalCloudPoints.size()], 1, globalCloudPoints.size()); + cvflann::Matrix distsMatrix(new float[globalCloudPoints.size()], 1, globalCloudPoints.size()); + int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, m_radius * m_radius, cvflann::SearchParams()); + idxCandidates.assign(indicesMatrix.data, indicesMatrix.data + nbFound); + dists.assign(distsMatrix.data, distsMatrix.data + nbFound); std::vector> desCandidates; std::vector idxBestCandidates; for (const auto &idx : idxCandidates) { - if ((idx != 0) && checkMatches[idx]) { + if (checkMatches[idx]) { desCandidates.push_back(globalCloudPoints[idx]->getDescriptor()); idxBestCandidates.push_back(idx); } From 2f8ad875533e4f94360faf85a0e5919aa32961d1 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Wed, 10 Feb 2021 16:49:59 +0100 Subject: [PATCH 08/21] fix: free memory of cvflann matrix --- src/SolARDescriptorMatcherKNNOpencv.cpp | 6 +++++- src/SolARMapFusionOpencv.cpp | 4 ++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/SolARDescriptorMatcherKNNOpencv.cpp b/src/SolARDescriptorMatcherKNNOpencv.cpp index dc394273..683fba0f 100644 --- a/src/SolARDescriptorMatcherKNNOpencv.cpp +++ b/src/SolARDescriptorMatcherKNNOpencv.cpp @@ -67,6 +67,10 @@ int radiusSearch(cvflann::KDTreeSingleIndex>& kdtree, const P int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, radius * radius, cvflann::SearchParams()); indices.assign(indicesMatrix.data, indicesMatrix.data + nbFound); dists.assign(distsMatrix.data, distsMatrix.data + nbFound); + delete indicesMatrix.data; + indicesMatrix.data = NULL; + delete distsMatrix.data; + distsMatrix.data = NULL; return nbFound; } @@ -207,7 +211,7 @@ IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const matches.clear(); float radiusValue = radius > 0 ? radius : m_radius; float matchingDistanceMaxValue = matchingDistanceMax > 0 ? matchingDistanceMax : m_matchingDistanceMax; - SRef descriptorFrame = frame->getDescriptors(); + const SRef& descriptorFrame = frame->getDescriptors(); if (descriptors.size() == 0 || descriptorFrame->getNbDescriptors() == 0) return IDescriptorMatcher::RetCode::DESCRIPTOR_EMPTY; diff --git a/src/SolARMapFusionOpencv.cpp b/src/SolARMapFusionOpencv.cpp index ea30b2f5..6e103120 100644 --- a/src/SolARMapFusionOpencv.cpp +++ b/src/SolARMapFusionOpencv.cpp @@ -95,6 +95,10 @@ FrameworkReturnCode SolARMapFusionOpencv::merge(SRef map, SRef int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, m_radius * m_radius, cvflann::SearchParams()); idxCandidates.assign(indicesMatrix.data, indicesMatrix.data + nbFound); dists.assign(distsMatrix.data, distsMatrix.data + nbFound); + delete indicesMatrix.data; + indicesMatrix.data = NULL; + delete distsMatrix.data; + distsMatrix.data = NULL; std::vector> desCandidates; std::vector idxBestCandidates; for (const auto &idx : idxCandidates) { From 548370afb8340e3814ab045f910b889650c0e57c Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Mon, 15 Feb 2021 19:44:42 +0100 Subject: [PATCH 09/21] fix: radius search using genericIndex instead of kdtreeSingleIndex --- src/SolARDescriptorMatcherKNNOpencv.cpp | 23 ++++++++--------------- src/SolARMapFusionOpencv.cpp | 19 ++++++------------- 2 files changed, 14 insertions(+), 28 deletions(-) diff --git a/src/SolARDescriptorMatcherKNNOpencv.cpp b/src/SolARDescriptorMatcherKNNOpencv.cpp index 683fba0f..3201aff0 100644 --- a/src/SolARDescriptorMatcherKNNOpencv.cpp +++ b/src/SolARDescriptorMatcherKNNOpencv.cpp @@ -44,7 +44,7 @@ SolARDescriptorMatcherKNNOpencv::~SolARDescriptorMatcherKNNOpencv() LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv destructor") } -cvflann::KDTreeSingleIndex> initKDTree(const std::vector &keypoints) +cv::flann::GenericIndex> initKDTree(const std::vector &keypoints) { cv::Mat_ features(0, 2); for (const auto &kp : keypoints) { @@ -52,25 +52,18 @@ cvflann::KDTreeSingleIndex> initKDTree(const std::vector samplesMatrix((float*)features.data, features.rows, features.cols); - cvflann::KDTreeSingleIndex> kdtree(samplesMatrix, indexParams); - kdtree.buildIndex(); + cv::flann::GenericIndex> kdtree(features, indexParams); return kdtree; } -int radiusSearch(cvflann::KDTreeSingleIndex>& kdtree, const Point2Df& query, const float & radius, std::vector & indices, std::vector & dists, const int & maxResults = 500) +int radiusSearch(cv::flann::GenericIndex>& kdtree, const Point2Df& query, const float & radius, std::vector & indices, std::vector & dists, const int & maxResults = 500) { std::vector pt2D = { query.getX(), query.getY() }; - cvflann::Matrix queryMatrix(pt2D.data(), 1, 2); - cvflann::Matrix indicesMatrix(new int[maxResults], 1, maxResults); - cvflann::Matrix distsMatrix(new float[maxResults], 1, maxResults); - int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, radius * radius, cvflann::SearchParams()); - indices.assign(indicesMatrix.data, indicesMatrix.data + nbFound); - dists.assign(distsMatrix.data, distsMatrix.data + nbFound); - delete indicesMatrix.data; - indicesMatrix.data = NULL; - delete distsMatrix.data; - distsMatrix.data = NULL; + std::vector tmpIndices(maxResults); + std::vector tmpDists(maxResults); + int nbFound = kdtree.radiusSearch(pt2D, tmpIndices, tmpDists, radius * radius, cvflann::SearchParams()); + indices.assign(tmpIndices.begin(), tmpIndices.begin() + nbFound); + dists.assign(tmpDists.begin(), tmpDists.begin() + nbFound); return nbFound; } diff --git a/src/SolARMapFusionOpencv.cpp b/src/SolARMapFusionOpencv.cpp index 6e103120..95825c89 100644 --- a/src/SolARMapFusionOpencv.cpp +++ b/src/SolARMapFusionOpencv.cpp @@ -78,9 +78,7 @@ FrameworkReturnCode SolARMapFusionOpencv::merge(SRef map, SRef features.push_back(row); } cvflann::KDTreeSingleIndexParams indexParams; - cvflann::Matrix samplesMatrix((float*)features.data, features.rows, features.cols); - cvflann::KDTreeSingleIndex> kdtree(samplesMatrix, indexParams); - kdtree.buildIndex(); + cv::flann::GenericIndex> kdtree(features, indexParams); // find correspondences for each point std::vector < std::pair, SRef>> duplicatedCPs; // first is local CP, second is global CP std::vector checkMatches(globalCloudPoints.size(), true); @@ -89,16 +87,11 @@ FrameworkReturnCode SolARMapFusionOpencv::merge(SRef map, SRef std::vector idxCandidates; std::vector dists; std::vector pt3D = { cp->getX(), cp->getY(), cp->getZ() }; - cvflann::Matrix queryMatrix(pt3D.data(), 1, 3); - cvflann::Matrix indicesMatrix(new int[globalCloudPoints.size()], 1, globalCloudPoints.size()); - cvflann::Matrix distsMatrix(new float[globalCloudPoints.size()], 1, globalCloudPoints.size()); - int nbFound = kdtree.radiusSearch(queryMatrix, indicesMatrix, distsMatrix, m_radius * m_radius, cvflann::SearchParams()); - idxCandidates.assign(indicesMatrix.data, indicesMatrix.data + nbFound); - dists.assign(distsMatrix.data, distsMatrix.data + nbFound); - delete indicesMatrix.data; - indicesMatrix.data = NULL; - delete distsMatrix.data; - distsMatrix.data = NULL; + std::vector indicesMatrix(globalCloudPoints.size()); + std::vector distsMatrix(globalCloudPoints.size()); + int nbFound = kdtree.radiusSearch(pt3D, indicesMatrix, distsMatrix, m_radius * m_radius, cvflann::SearchParams()); + idxCandidates.assign(indicesMatrix.begin(), indicesMatrix.begin() + nbFound); + dists.assign(distsMatrix.begin(), distsMatrix.begin() + nbFound); std::vector> desCandidates; std::vector idxBestCandidates; for (const auto &idx : idxCandidates) { From caabe9a6725b15a9f84074cbe1e6a8ee52f954bb Mon Sep 17 00:00:00 2001 From: Thibaud Date: Tue, 16 Feb 2021 09:14:23 +0100 Subject: [PATCH 10/21] fix: video resize condition --- src/SolARVideoAsCameraOpencv.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/SolARVideoAsCameraOpencv.cpp b/src/SolARVideoAsCameraOpencv.cpp index 1e22a187..23f5af57 100644 --- a/src/SolARVideoAsCameraOpencv.cpp +++ b/src/SolARVideoAsCameraOpencv.cpp @@ -46,8 +46,8 @@ using namespace datastructure; { return FrameworkReturnCode::_ERROR_LOAD_IMAGE; } - unsigned int w=cvFrame.rows; - unsigned int h=cvFrame.cols; + unsigned int w=cvFrame.cols; + unsigned int h=cvFrame.rows; if(w!=m_parameters.resolution.width || h!=m_parameters.resolution.height) cv::resize(cvFrame, cvFrame, cv::Size((int)m_parameters.resolution.width,(int)m_parameters.resolution.height), 0, 0); From fc803d0085d1a954cfa8b626e7bd8bace60f7f18 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Tue, 16 Feb 2021 11:15:04 +0100 Subject: [PATCH 11/21] fix: flann in KNN Matcher component --- src/SolARDescriptorMatcherKNNOpencv.cpp | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/src/SolARDescriptorMatcherKNNOpencv.cpp b/src/SolARDescriptorMatcherKNNOpencv.cpp index 3201aff0..64ee453d 100644 --- a/src/SolARDescriptorMatcherKNNOpencv.cpp +++ b/src/SolARDescriptorMatcherKNNOpencv.cpp @@ -61,7 +61,9 @@ int radiusSearch(cv::flann::GenericIndex>& kdtree, const Po std::vector pt2D = { query.getX(), query.getY() }; std::vector tmpIndices(maxResults); std::vector tmpDists(maxResults); + LOG_DEBUG("OK__4: {}", tmpIndices.size()); int nbFound = kdtree.radiusSearch(pt2D, tmpIndices, tmpDists, radius * radius, cvflann::SearchParams()); + LOG_DEBUG("OK__4: {}", nbFound); indices.assign(tmpIndices.begin(), tmpIndices.begin() + nbFound); dists.assign(tmpDists.begin(), tmpDists.begin() + nbFound); return nbFound; @@ -233,16 +235,25 @@ IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const // init kd tree to accelerate searching const std::vector &keypointsFrame = frame->getKeypoints(); - auto kdtree = initKDTree(keypointsFrame); - + cv::Mat_ features(0, 2); + for (const auto &kp : keypointsFrame) { + cv::Mat row = (cv::Mat_(1, 2) << kp.getX(), kp.getY()); + features.push_back(row); + } + cvflann::KDTreeSingleIndexParams indexParams; + cv::flann::GenericIndex> kdtree(features, indexParams); // Match each descriptor to descriptors of frame in a corresponding region std::vector checkMatches(keypointsFrame.size(), true); int idx = 0; for (const auto &it : cvDescriptors) { std::vector idxCandidates; std::vector dists; - Point2Df query(points2D[idx].getX(), points2D[idx].getY()); - int nbFound = radiusSearch(kdtree, query, radiusValue, idxCandidates, dists, keypointsFrame.size()); + std::vector query = { points2D[idx].getX(), points2D[idx].getY() }; + std::vector indicesMatrix(keypointsFrame.size()); + std::vector distsMatrix(keypointsFrame.size()); + int nbFound = kdtree.radiusSearch(query, indicesMatrix, distsMatrix, radiusValue * radiusValue, cvflann::SearchParams()); + idxCandidates.assign(indicesMatrix.begin(), indicesMatrix.begin() + nbFound); + dists.assign(distsMatrix.begin(), distsMatrix.begin() + nbFound); if (nbFound > 0) { float bestDist = std::numeric_limits::max(); float bestDist2 = std::numeric_limits::max(); From b1b340238b7635cebf9b72a314ab13f611d466df Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Tue, 16 Feb 2021 11:24:57 +0100 Subject: [PATCH 12/21] fix: radius search in other functions --- src/SolARDescriptorMatcherKNNOpencv.cpp | 41 ++++++++----------------- 1 file changed, 13 insertions(+), 28 deletions(-) diff --git a/src/SolARDescriptorMatcherKNNOpencv.cpp b/src/SolARDescriptorMatcherKNNOpencv.cpp index 64ee453d..a0fe7837 100644 --- a/src/SolARDescriptorMatcherKNNOpencv.cpp +++ b/src/SolARDescriptorMatcherKNNOpencv.cpp @@ -44,31 +44,6 @@ SolARDescriptorMatcherKNNOpencv::~SolARDescriptorMatcherKNNOpencv() LOG_DEBUG(" SolARDescriptorMatcherKNNOpencv destructor") } -cv::flann::GenericIndex> initKDTree(const std::vector &keypoints) -{ - cv::Mat_ features(0, 2); - for (const auto &kp : keypoints) { - cv::Mat row = (cv::Mat_(1, 2) << kp.getX(), kp.getY()); - features.push_back(row); - } - cvflann::KDTreeSingleIndexParams indexParams; - cv::flann::GenericIndex> kdtree(features, indexParams); - return kdtree; -} - -int radiusSearch(cv::flann::GenericIndex>& kdtree, const Point2Df& query, const float & radius, std::vector & indices, std::vector & dists, const int & maxResults = 500) -{ - std::vector pt2D = { query.getX(), query.getY() }; - std::vector tmpIndices(maxResults); - std::vector tmpDists(maxResults); - LOG_DEBUG("OK__4: {}", tmpIndices.size()); - int nbFound = kdtree.radiusSearch(pt2D, tmpIndices, tmpDists, radius * radius, cvflann::SearchParams()); - LOG_DEBUG("OK__4: {}", nbFound); - indices.assign(tmpIndices.begin(), tmpIndices.begin() + nbFound); - dists.assign(tmpDists.begin(), tmpDists.begin() + nbFound); - return nbFound; -} - IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::match( SRef desc1,SRef desc2, std::vector& matches){ @@ -308,7 +283,13 @@ IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const // init kd tree to accelerate searching const std::vector &keypointsLastFrame = lastFrame->getKeypoints(); - auto kdtree = initKDTree(keypointsLastFrame); + cv::Mat_ features(0, 2); + for (const auto &kp : keypointsLastFrame) { + cv::Mat row = (cv::Mat_(1, 2) << kp.getX(), kp.getY()); + features.push_back(row); + } + cvflann::KDTreeSingleIndexParams indexParams; + cv::flann::GenericIndex> kdtree(features, indexParams); // Match each descriptor of the current frame to descriptors of the last frame in a corresponding region std::vector checkMatches(keypointsLastFrame.size(), true); @@ -316,9 +297,13 @@ IDescriptorMatcher::RetCode SolARDescriptorMatcherKNNOpencv::matchInRegion(const for (int i = 0; i < keypointsCurrentFrame.size(); ++i) { std::vector idxCandidates; std::vector dists; - Point2Df queryPt2D(keypointsCurrentFrame[i].getX(), keypointsCurrentFrame[i].getY()); + std::vector query = { keypointsCurrentFrame[i].getX(), keypointsCurrentFrame[i].getY() }; + std::vector indicesMatrix(keypointsLastFrame.size()); + std::vector distsMatrix(keypointsLastFrame.size()); + int nbFound = kdtree.radiusSearch(query, indicesMatrix, distsMatrix, radiusValue * radiusValue, cvflann::SearchParams()); + idxCandidates.assign(indicesMatrix.begin(), indicesMatrix.begin() + nbFound); + dists.assign(distsMatrix.begin(), distsMatrix.begin() + nbFound); cv::Mat queryDes = cvDesCurrentFrame.row(i); - int nbFound = radiusSearch(kdtree, queryPt2D, radiusValue, idxCandidates, dists, keypointsLastFrame.size()); if (nbFound > 0) { float bestDist = std::numeric_limits::max(); float bestDist2 = std::numeric_limits::max(); From 8fdb1ea942714bef08f496c47b64857a20cc37ce Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Wed, 24 Feb 2021 22:15:56 +0100 Subject: [PATCH 13/21] add corner refinement component --- SolARModuleOpenCV.pri | 2 + interfaces/SolARCornerRefinementOpencv.h | 68 +++++++++++++++++++++ interfaces/SolARModuleOpencv_traits.h | 5 ++ src/SolARCornerRefinementOpencv.cpp | 77 ++++++++++++++++++++++++ src/SolARModuleOpencv.cpp | 6 ++ 5 files changed, 158 insertions(+) create mode 100644 interfaces/SolARCornerRefinementOpencv.h create mode 100644 src/SolARCornerRefinementOpencv.cpp diff --git a/SolARModuleOpenCV.pri b/SolARModuleOpenCV.pri index afdc2eb2..33289675 100644 --- a/SolARModuleOpenCV.pri +++ b/SolARModuleOpenCV.pri @@ -6,6 +6,7 @@ HEADERS += interfaces/SolAR2D3DcorrespondencesFinderOpencv.h \ interfaces/SolARCameraOpencv.h \ interfaces/SolARContoursExtractorOpencv.h \ interfaces/SolARContoursFilterBinaryMarkerOpencv.h \ + interfaces/SolARCornerRefinementOpencv.h \ interfaces/SolARDescriptorMatcherHammingBruteForceOpencv.h \ interfaces/SolARDescriptorMatcherKNNOpencv.h \ interfaces/SolARDescriptorMatcherRadiusOpencv.h \ @@ -70,6 +71,7 @@ SOURCES += src/AKAZE2/akaze.cpp \ src/SolARCameraOpencv.cpp \ src/SolARContoursExtractorOpencv.cpp \ src/SolARContoursFilterBinaryMarkerOpencv.cpp \ + src/SolARCornerRefinementOpencv.cpp \ src/SolARDescriptorMatcherHammingBruteForceOpencv.cpp \ src/SolARDescriptorMatcherKNNOpencv.cpp \ src/SolARDescriptorMatcherRadiusOpencv.cpp \ diff --git a/interfaces/SolARCornerRefinementOpencv.h b/interfaces/SolARCornerRefinementOpencv.h new file mode 100644 index 00000000..90cd9fad --- /dev/null +++ b/interfaces/SolARCornerRefinementOpencv.h @@ -0,0 +1,68 @@ +/** + * @copyright Copyright (c) 2017 B-com http://www.b-com.com/ + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#ifndef SOLARCORNERREFINEMENTOPENCV_H +#define SOLARCORNERREFINEMENTOPENCV_H + +#include "xpcf/component/ConfigurableBase.h" +#include "SolAROpencvAPI.h" +#include "api/features/ICornerRefinement.h" +#include "opencv2/core.hpp" +#include + +namespace SolAR { +namespace MODULES { +namespace OPENCV { + +/** +* @class SolARCornerRefinementOpencv +* @brief Refine the corner locations. +* UUID: ddae46ca-1657-4301-a87d-f2dcfa6265d0 +* +*/ + +class SOLAROPENCV_EXPORT_API SolARCornerRefinementOpencv : public org::bcom::xpcf::ConfigurableBase, + public api::features::ICornerRefinement +{ +public: + /// @brief SolARCornerRefinementOpencv constructor + SolARCornerRefinementOpencv(); + + /// @brief SolARCornerRefinementOpencv default destructor + ~SolARCornerRefinementOpencv() = default; + + /// @brief This method refines the corner locations + /// @param[in] image Input image on which we are extracting keypoints. + /// @param[in,out] corners Initial coordinates of the input corners and refined coordinates provided for output. + void refine(const SRef image, std::vector & corners) override; + + org::bcom::xpcf::XPCFErrorCode onConfigured() override final; + + void unloadComponent () override final; + +private: + uint32_t m_nbMaxIters = 40; + float m_minAccuracy = 0.01; + cv::TermCriteria m_termcrit; + uint32_t m_winSize = 5; + cv::Size m_subPixWinSize; +}; + +} +} +} + +#endif // SOLARCORNERREFINEMENTOPENCV_H diff --git a/interfaces/SolARModuleOpencv_traits.h b/interfaces/SolARModuleOpencv_traits.h index bceade43..052f2ba9 100644 --- a/interfaces/SolARModuleOpencv_traits.h +++ b/interfaces/SolARModuleOpencv_traits.h @@ -77,6 +77,7 @@ class SolARUndistortPointsOpencv; class SolARVideoAsCameraOpencv; class SolARDeviceDataLoader; class SolARMapFusionOpencv; +class SolARCornerRefinementOpencv; } } } @@ -324,5 +325,9 @@ XPCF_DEFINE_COMPONENT_TRAITS(SolAR::MODULES::OPENCV::SolARMapFusionOpencv, "bc661909-0185-40a4-a5e6-e52280e7b338", "SolARMapFusionOpencv", "Merge local map or floating map in the global map.") +XPCF_DEFINE_COMPONENT_TRAITS(SolAR::MODULES::OPENCV::SolARCornerRefinementOpencv, + "ddae46ca-1657-4301-a87d-f2dcfa6265d0", + "SolARCornerRefinementOpencv", + "Refine the corner locations.") #endif // SOLARMODULEOPENCV_TRAITS_H diff --git a/src/SolARCornerRefinementOpencv.cpp b/src/SolARCornerRefinementOpencv.cpp new file mode 100644 index 00000000..f8fc6519 --- /dev/null +++ b/src/SolARCornerRefinementOpencv.cpp @@ -0,0 +1,77 @@ +/** + * @copyright Copyright (c) 2017 B-com http://www.b-com.com/ + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include "SolARCornerRefinementOpencv.h" +#include "SolARImageConvertorOpencv.h" +#include "SolAROpenCVHelper.h" +#include "core/Log.h" +#include +namespace xpcf = org::bcom::xpcf; + +XPCF_DEFINE_FACTORY_CREATE_INSTANCE(SolAR::MODULES::OPENCV::SolARCornerRefinementOpencv) + +namespace SolAR { +using namespace datastructure; +namespace MODULES { +namespace OPENCV { + +SolARCornerRefinementOpencv::SolARCornerRefinementOpencv() :ConfigurableBase(xpcf::toUUID()) +{ + declareInterface(this); + declareProperty("nbMaxIters", m_nbMaxIters); + declareProperty("minAccuracy", m_minAccuracy); + declareProperty("winSize", m_winSize); + LOG_DEBUG(" SolARFiducialMarkerPoseEstimatorOpencv constructor") +} + +xpcf::XPCFErrorCode SolARCornerRefinementOpencv::onConfigured() +{ + m_termcrit = cv::TermCriteria(cv::TermCriteria::COUNT | cv::TermCriteria::EPS, m_nbMaxIters, m_minAccuracy); + m_subPixWinSize = cv::Size(m_winSize, m_winSize); + LOG_DEBUG(" SolARCornerRefinementOpencv configured"); + return xpcf::XPCFErrorCode::_SUCCESS; +} + +void SolARCornerRefinementOpencv::refine(const SRef image, std::vector& corners) +{ + // transform all SolAR data to openCv data + SRef convertedImage = image; + if (image->getImageLayout() != Image::ImageLayout::LAYOUT_GREY) { + // input Image not in grey levels : convert it ! + SolARImageConvertorOpencv convertor; + convertedImage = xpcf::utils::make_shared(Image::ImageLayout::LAYOUT_GREY, Image::PixelOrder::INTERLEAVED, image->getDataType()); + convertor.convert(image, convertedImage); + } + cv::Mat imageOpencv; + SolAROpenCVHelper::mapToOpenCV(convertedImage, imageOpencv); + + std::vector cornersOpencv; + for (const auto &cor : corners) + cornersOpencv.push_back(cv::Point2f(cor.getX(), cor.getY())); + + // refine + cv::cornerSubPix(imageOpencv, cornersOpencv, m_subPixWinSize, cv::Size(-1, -1), m_termcrit); + + // return output + corners.clear(); + for (const auto &cor : cornersOpencv) + corners.push_back(datastructure::Point2Df(cor.x, cor.y)); +} + +} +} +} + diff --git a/src/SolARModuleOpencv.cpp b/src/SolARModuleOpencv.cpp index 0844f588..502fd6e2 100644 --- a/src/SolARModuleOpencv.cpp +++ b/src/SolARModuleOpencv.cpp @@ -65,6 +65,7 @@ #include "SolARImagesAsCameraOpencv.h" #include "SolARDeviceDataLoader.h" #include "SolARMapFusionOpencv.h" +#include "SolARCornerRefinementOpencv.h" namespace xpcf=org::bcom::xpcf; @@ -266,6 +267,10 @@ extern "C" XPCF_MODULEHOOKS_API xpcf::XPCFErrorCode XPCF_getComponent(const boos { errCode = xpcf::tryCreateComponent(componentUUID, interfaceRef); } + if (errCode != xpcf::XPCFErrorCode::_SUCCESS) + { + errCode = xpcf::tryCreateComponent(componentUUID, interfaceRef); + } return errCode; } @@ -319,4 +324,5 @@ XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARImagesAsCameraOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARDeviceDataLoader) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARMapFusionOpencv) XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARUndistortPointsOpencv) +XPCF_ADD_COMPONENT(SolAR::MODULES::OPENCV::SolARCornerRefinementOpencv) XPCF_END_COMPONENTS_DECLARATION From d8df1d1d08602ab44abdd7cc078293123483bfd2 Mon Sep 17 00:00:00 2001 From: "BCOM\\nduong" Date: Thu, 18 Mar 2021 17:22:06 +0100 Subject: [PATCH 14/21] feat: eliminate keypoint detection in borders of image. fix: unscale of poses of keyframes in map fusion --- interfaces/SolARKeypointDetectorOpencv.h | 1 + src/SolARKeypointDetectorOpencv.cpp | 11 +++++++++-- src/SolARMapFusionOpencv.cpp | 1 - 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/interfaces/SolARKeypointDetectorOpencv.h b/interfaces/SolARKeypointDetectorOpencv.h index c5efe2c4..c306a7ae 100644 --- a/interfaces/SolARKeypointDetectorOpencv.h +++ b/interfaces/SolARKeypointDetectorOpencv.h @@ -107,6 +107,7 @@ class SOLAROPENCV_EXPORT_API SolARKeypointDetectorOpencv : public org::bcom::xpc cv::KeyPointsFilter kptsFilter; int m_nbGridWidth = 20; int m_nbGridHeight = 20; + float m_borderRatio = 0.01f; }; diff --git a/src/SolARKeypointDetectorOpencv.cpp b/src/SolARKeypointDetectorOpencv.cpp index a32db07c..00ce20c0 100644 --- a/src/SolARKeypointDetectorOpencv.cpp +++ b/src/SolARKeypointDetectorOpencv.cpp @@ -56,6 +56,7 @@ SolARKeypointDetectorOpencv::SolARKeypointDetectorOpencv():ConfigurableBase(xpcf declareProperty("nbOctaves", m_nbOctaves); declareProperty("nbGridWidth", m_nbGridWidth); declareProperty("nbGridHeight", m_nbGridHeight); + declareProperty("borderRatio", m_borderRatio); declareProperty("type", m_type); LOG_DEBUG("SolARKeypointDetectorOpencv constructor"); } @@ -186,9 +187,15 @@ void SolARKeypointDetectorOpencv::detect(const SRef image, std::vector> gridKps; + int borderWidth = static_cast(m_borderRatio * image->getWidth()); + int borderHeight = static_cast(m_borderRatio * image->getHeight()); + int widthToExtract = image->getWidth() - 2 * borderWidth; + int heightToExtract = image->getHeight() - 2 * borderHeight; for (const auto &it : kpts) { - int id_width = static_cast(std::floor(it.pt.x * m_nbGridWidth / image->getWidth())); - int id_height = static_cast(std::floor(it.pt.y * m_nbGridHeight / image->getHeight())); + int id_width = static_cast(std::floor((it.pt.x - borderWidth) * m_nbGridWidth / widthToExtract)); + int id_height = static_cast(std::floor((it.pt.y - borderHeight) * m_nbGridHeight / heightToExtract)); + if ((id_width < 0) || (id_width >= m_nbGridWidth) || (id_height < 0) || (id_height >= m_nbGridHeight)) + continue; gridKps[id_height * m_nbGridWidth + id_width].push_back(it); } // get best feature per cell diff --git a/src/SolARMapFusionOpencv.cpp b/src/SolARMapFusionOpencv.cpp index 95825c89..bc7a2abc 100644 --- a/src/SolARMapFusionOpencv.cpp +++ b/src/SolARMapFusionOpencv.cpp @@ -207,7 +207,6 @@ void SolARMapFusionOpencv::fuseMap(const std::vectorsetPose(kfPose); uint32_t idxOld = kf->getId(); From 37f3af1e8edb0b082d5f435ee5980625f39a1812 Mon Sep 17 00:00:00 2001 From: Jerome Date: Tue, 13 Jul 2021 10:21:47 +0200 Subject: [PATCH 15/21] Update camera calibration test to load configuration file --- .../SolARCameraCalibrationOpenCVTest.cpp | 76 +++++++++++++------ ...lARTest_ModuleOpenCV_CameraCalibration.pro | 4 + ...st_ModuleOpenCV_CameraCalibration_conf.xml | 9 +++ 3 files changed, 66 insertions(+), 23 deletions(-) create mode 100644 tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration_conf.xml diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp index d91baa19..552a8a16 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp @@ -19,10 +19,7 @@ // ADD COMPONENTS HEADERS HERE, e.g #include "SolarComponent.h" -#include "SolARImageLoaderOpencv.h" -#include "SolARImageViewerOpencv.h" -#include "SolARCameraCalibrationOpencv.h" -#include "SolARCameraOpencv.h" +#include "api/input/devices/ICameraCalibration.h" #include "core/Log.h" @@ -33,7 +30,6 @@ using namespace std; using namespace SolAR; using namespace SolAR::datastructure; using namespace SolAR::api; -using namespace SolAR::MODULES::OPENCV; namespace xpcf = org::bcom::xpcf; @@ -56,20 +52,39 @@ void printHelp() { int calibratio_run(int cameraId) { - SRef inputImage; +#if NDEBUG + boost::log::core::get()->set_logging_enabled(false); +#endif - std::string calib_config = std::string("../../data/chessboard_config.yml"); - std::ifstream ifs(calib_config.c_str()); - if (!ifs) { - LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); - printHelp(); - return -1; - } + LOG_ADD_LOG_TO_CONSOLE(); + + /* instantiate component manager*/ + /* this is needed in dynamic mode */ + SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); - auto cameraCalibration =xpcf::ComponentFactory::createInstance()->bindTo(); + if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) + { + LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") + return -1; + } + + std::string calib_config = std::string("../../data/chessboard_config.yml"); + std::ifstream ifs(calib_config.c_str()); + if (!ifs) { + LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); + printHelp(); + return -1; + } std::string calib_output = std::string("../../data/camera_calibration.yml"); + // declare and create components + LOG_INFO("Start creating components"); + + auto cameraCalibration = xpcfComponentManager->resolve(); + + SRef inputImage; + if (cameraCalibration->setParameters(calib_config)) { cameraCalibration->calibrate(cameraId, calib_output); @@ -85,21 +100,36 @@ int calibratio_run(int cameraId) { int calibratio_run(std::string& video) { - SRef inputImage; + LOG_ADD_LOG_TO_CONSOLE(); + + /* instantiate component manager*/ + /* this is needed in dynamic mode */ + SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); - auto cameraCalibration =xpcf::ComponentFactory::createInstance()->bindTo(); + if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) + { + LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") + return -1; + } std::string calib_config = std::string("../../data/chessboard_config.yml"); - std::ifstream ifs(calib_config.c_str()); - if (!ifs) { - LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); - printHelp(); - return -1; - } + std::ifstream ifs(calib_config.c_str()); + if (!ifs) { + LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); + printHelp(); + return -1; + } std::string calib_output = std::string("../../data/camera_calibration.yml"); - if (cameraCalibration->setParameters(calib_config)) + // declare and create components + LOG_INFO("Start creating components"); + + auto cameraCalibration = xpcfComponentManager->resolve(); + + SRef inputImage; + + if (cameraCalibration->setParameters(calib_config)) { cameraCalibration->calibrate(video, calib_output); } diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro index a4b43f69..2e6b7d92 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration.pro @@ -70,6 +70,10 @@ android { ANDROID_ABIS="arm64-v8a" } +configfile.path = $${TARGETDEPLOYDIR}/ +configfile.files = $${PWD}/SolARTest_ModuleOpenCV_CameraCalibration_conf.xml +INSTALLS += configfile + DISTFILES += \ packagedependencies.txt diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration_conf.xml b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration_conf.xml new file mode 100644 index 00000000..e2c89682 --- /dev/null +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARTest_ModuleOpenCV_CameraCalibration_conf.xml @@ -0,0 +1,9 @@ + + + + + + + + + From f57204ffcb8a9ff7cafdd14c8cea3b33933a8881 Mon Sep 17 00:00:00 2001 From: Jerome Date: Tue, 13 Jul 2021 10:23:01 +0200 Subject: [PATCH 16/21] Remove unused variables --- tests/run.sh | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) create mode 100644 tests/run.sh diff --git a/tests/run.sh b/tests/run.sh new file mode 100644 index 00000000..2b1330f3 --- /dev/null +++ b/tests/run.sh @@ -0,0 +1,17 @@ +#!/bin/bash + +export XPCF_MODULE_ROOT=~/.remaken/packages/linux-gcc +echo "XPCF_MODULE_ROOT=$XPCF_MODULE_ROOT" + +ld_library_path="./" +for modulePath in $(grep -o "\$XPCF_MODULE_ROOT.*lib" $1_conf.xml) +do + modulePath=${modulePath/"\$XPCF_MODULE_ROOT"/${XPCF_MODULE_ROOT}} + if ! [[ $ld_library_path =~ "$modulePath/x86_64/shared/debug" ]] + then + ld_library_path=$ld_library_path:$modulePath/x86_64/shared/debug + fi +done + +echo "LD_LIBRARY_PATH=$ld_library_path $1" +LD_LIBRARY_PATH=$ld_library_path $1 From c1bfe91320497f35c236a18bbc6e5e137b5d128e Mon Sep 17 00:00:00 2001 From: Jerome Date: Tue, 13 Jul 2021 10:53:02 +0200 Subject: [PATCH 17/21] Add missing boost header for logs --- .../SolARCameraCalibrationOpenCVTest.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp index 552a8a16..19a59db4 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp @@ -23,6 +23,7 @@ #include "core/Log.h" +#include #include #include From e0765d7b100e90c939e78fc794fa2adfa3b46451 Mon Sep 17 00:00:00 2001 From: Jerome Date: Tue, 13 Jul 2021 10:53:13 +0200 Subject: [PATCH 18/21] Remove unused variables --- tests/SolARTest_ModuleOpenCV_DescriptorMatcher/main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/main.cpp b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/main.cpp index fd145320..8b880aba 100644 --- a/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/main.cpp +++ b/tests/SolARTest_ModuleOpenCV_DescriptorMatcher/main.cpp @@ -90,8 +90,6 @@ int main(int argc,char** argv) SRef descriptors1; SRef descriptors2; std::vector matches; - std::vector> matchedKeypoints1; - std::vector> matchedKeypoints2; SRef viewerImageAKAZE, viewerImageORB, viewerImageSIFT; // Start From baf143af9b29133cc9487778325e02c9d5a86789 Mon Sep 17 00:00:00 2001 From: Jerome Date: Tue, 13 Jul 2021 14:23:32 +0200 Subject: [PATCH 19/21] Remove unused package and source code --- .../SolARCameraCalibrationOpenCVTest.cpp | 145 +++++++++--------- 1 file changed, 76 insertions(+), 69 deletions(-) diff --git a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp index 19a59db4..4c83ea9d 100644 --- a/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp +++ b/tests/SolARTest_ModuleOpenCV_CameraCalibration/SolARCameraCalibrationOpenCVTest.cpp @@ -15,18 +15,15 @@ */ #include +#include #include // ADD COMPONENTS HEADERS HERE, e.g #include "SolarComponent.h" +#include "xpcf/xpcf.h" #include "api/input/devices/ICameraCalibration.h" - #include "core/Log.h" -#include -#include -#include - using namespace std; using namespace SolAR; using namespace SolAR::datastructure; @@ -58,43 +55,47 @@ int calibratio_run(int cameraId) { #endif LOG_ADD_LOG_TO_CONSOLE(); - - /* instantiate component manager*/ - /* this is needed in dynamic mode */ - SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); - - if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) - { - LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") - return -1; + try { + /* instantiate component manager*/ + /* this is needed in dynamic mode */ + SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); + + if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) + { + LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") + return -1; + } + + std::string calib_config = std::string("../../data/chessboard_config.yml"); + std::ifstream ifs(calib_config.c_str()); + if (!ifs) { + LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); + printHelp(); + return -1; + } + + std::string calib_output = std::string("../../data/camera_calibration.yml"); + + // declare and create components + LOG_INFO("Start creating components"); + + SRef cameraCalibration = xpcfComponentManager->resolve(); + + if (cameraCalibration->setParameters(calib_config)) + { + cameraCalibration->calibrate(cameraId, calib_output); + } + else + { + printHelp(); + } } - std::string calib_config = std::string("../../data/chessboard_config.yml"); - std::ifstream ifs(calib_config.c_str()); - if (!ifs) { - LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); - printHelp(); + catch (xpcf::Exception e) + { + LOG_ERROR ("The following exception has been catch : {}", e.what()); return -1; } - - std::string calib_output = std::string("../../data/camera_calibration.yml"); - - // declare and create components - LOG_INFO("Start creating components"); - - auto cameraCalibration = xpcfComponentManager->resolve(); - - SRef inputImage; - - if (cameraCalibration->setParameters(calib_config)) - { - cameraCalibration->calibrate(cameraId, calib_output); - } - else - { - printHelp(); - } - return 0; } @@ -103,42 +104,48 @@ int calibratio_run(std::string& video) { LOG_ADD_LOG_TO_CONSOLE(); - /* instantiate component manager*/ - /* this is needed in dynamic mode */ - SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); - - if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) - { - LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") - return -1; + try{ + /* instantiate component manager*/ + /* this is needed in dynamic mode */ + SRef xpcfComponentManager = xpcf::getComponentManagerInstance(); + + if(xpcfComponentManager->load("SolARTest_ModuleOpenCV_CameraCalibration_conf.xml")!=org::bcom::xpcf::_SUCCESS) + { + LOG_ERROR("Failed to load the configuration file SolARTest_ModuleOpenCV_CameraCalibration_conf.xml") + return -1; + } + + std::string calib_config = std::string("../../data/chessboard_config.yml"); + std::ifstream ifs(calib_config.c_str()); + if (!ifs) { + LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); + printHelp(); + return -1; + } + + std::string calib_output = std::string("../../data/camera_calibration.yml"); + + // declare and create components + LOG_INFO("Start creating components"); + + SRef cameraCalibration = xpcfComponentManager->resolve(); + + if (cameraCalibration->setParameters(calib_config)) + { + cameraCalibration->calibrate(video, calib_output); + } + else + { + printHelp(); + } } - std::string calib_config = std::string("../../data/chessboard_config.yml"); - std::ifstream ifs(calib_config.c_str()); - if (!ifs) { - LOG_ERROR("Calibration config File {} does not exist", calib_config.c_str()); - printHelp(); + catch (xpcf::Exception e) + { + LOG_ERROR ("The following exception has been catch : {}", e.what()); return -1; } - std::string calib_output = std::string("../../data/camera_calibration.yml"); - - // declare and create components - LOG_INFO("Start creating components"); - - auto cameraCalibration = xpcfComponentManager->resolve(); - - SRef inputImage; - - if (cameraCalibration->setParameters(calib_config)) - { - cameraCalibration->calibrate(video, calib_output); - } - else - { - printHelp(); - } - return 0; } int main(int argc, char* argv[]) { From 10a095abf7b52b9f5e872aebd5296e39e2f31b7d Mon Sep 17 00:00:00 2001 From: Jean-Marie HENAFF Date: Fri, 16 Jul 2021 15:33:00 +0200 Subject: [PATCH 20/21] Better error handling when setting resolution of camera --- src/SolARCameraOpencv.cpp | 29 +++++++++++++++++++++++++++-- src/SolARImagesAsCameraOpencv.cpp | 29 +++++++++++++++++++++++++++-- src/SolARVideoAsCameraOpencv.cpp | 23 +++++++++++++++++++++-- 3 files changed, 75 insertions(+), 6 deletions(-) diff --git a/src/SolARCameraOpencv.cpp b/src/SolARCameraOpencv.cpp index fbcf1033..45533791 100644 --- a/src/SolARCameraOpencv.cpp +++ b/src/SolARCameraOpencv.cpp @@ -63,8 +63,33 @@ namespace OPENCV { LOG_INFO("Camera using {} * {} resolution", m_parameters.resolution.width ,m_parameters.resolution.height) if (m_is_resolution_set) { - m_capture.set(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width ); - m_capture.set(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height ); + bool setResolutionFailed = false; + + auto setResolution = [&] + (cv::VideoCaptureProperties dimensionProp, + uint32_t value, + std::string dimensionName) + { + bool setResDimOk = m_capture.set(dimensionProp, value); + + if (!setResDimOk || m_capture.get(dimensionProp) != value) + { + setResolutionFailed = true; + LOG_ERROR("Cannot set camera {} to {}", dimensionName, value); + if (!setResDimOk) + { + LOG_WARNING( "Note: cv::VideoCapture::set() returned 'true'"); + } + } + }; + + setResolution(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width, "width"); + setResolution(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height, "height"); + + if ( setResolutionFailed ) + { + return FrameworkReturnCode::_ERROR_; + } } else { // set default resolution : get camera resolution ? or force camera resolution from default resolution values ? diff --git a/src/SolARImagesAsCameraOpencv.cpp b/src/SolARImagesAsCameraOpencv.cpp index 44e0b054..4f790a6b 100644 --- a/src/SolARImagesAsCameraOpencv.cpp +++ b/src/SolARImagesAsCameraOpencv.cpp @@ -43,6 +43,11 @@ namespace OPENCV { if(!cvFrame.data) return FrameworkReturnCode::_ERROR_LOAD_IMAGE; + unsigned int w=cvFrame.cols; + unsigned int h=cvFrame.rows; + if(w!=m_parameters.resolution.width || h!=m_parameters.resolution.height) + cv::resize(cvFrame, cvFrame, cv::Size((int)m_parameters.resolution.width,(int)m_parameters.resolution.height), 0, 0); + return SolAROpenCVHelper::convertToSolar(cvFrame,img); } @@ -58,8 +63,28 @@ namespace OPENCV { { if (m_is_resolution_set) { - m_capture.set(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width ); - m_capture.set(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height ); + LOG_INFO("Camera using {} * {} resolution", m_parameters.resolution.width ,m_parameters.resolution.height) + + auto setResolution = [&] + (cv::VideoCaptureProperties dimensionProp, + uint32_t value, + std::string dimensionName) + { + bool setResDimOk = m_capture.set(dimensionProp, value); + + if (!setResDimOk || m_capture.get(dimensionProp) != value) + { + LOG_WARNING("Cannot set camera {} to {}. Will fallback to cv::resize() each frame", dimensionName, value); + if (!setResDimOk) + { + LOG_WARNING( "Note: cv::VideoCapture::set() returned 'true'"); + } + } + }; + + setResolution(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width, "width"); + setResolution(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height, "height"); + } return FrameworkReturnCode::_SUCCESS; } diff --git a/src/SolARVideoAsCameraOpencv.cpp b/src/SolARVideoAsCameraOpencv.cpp index 23f5af57..28270296 100644 --- a/src/SolARVideoAsCameraOpencv.cpp +++ b/src/SolARVideoAsCameraOpencv.cpp @@ -66,8 +66,27 @@ using namespace datastructure; { if (m_is_resolution_set) { - m_capture.set(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width ); - m_capture.set(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height ); + LOG_INFO("Camera using {} * {} resolution", m_parameters.resolution.width ,m_parameters.resolution.height) + + auto setResolution = [&] + (cv::VideoCaptureProperties dimensionProp, + uint32_t value, + std::string dimensionName) + { + bool setResDimOk = m_capture.set(dimensionProp, value); + + if (!setResDimOk || m_capture.get(dimensionProp) != value) + { + LOG_WARNING("Cannot set camera {} to {}. Will fallback to cv::resize() each frame", dimensionName, value); + if (!setResDimOk) + { + LOG_WARNING( "Note: cv::VideoCapture::set() returned 'true'"); + } + } + }; + + setResolution(cv::CAP_PROP_FRAME_WIDTH, m_parameters.resolution.width, "width"); + setResolution(cv::CAP_PROP_FRAME_HEIGHT, m_parameters.resolution.height, "height"); } return FrameworkReturnCode::_SUCCESS; } From 5b2d3dbfebdade0b02fd554a298165dec7f70b58 Mon Sep 17 00:00:00 2001 From: Jean-Marie HENAFF Date: Fri, 16 Jul 2021 16:04:39 +0200 Subject: [PATCH 21/21] Make string param of lambda a const ref --- src/SolARCameraOpencv.cpp | 2 +- src/SolARImagesAsCameraOpencv.cpp | 2 +- src/SolARVideoAsCameraOpencv.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/SolARCameraOpencv.cpp b/src/SolARCameraOpencv.cpp index 45533791..d21cf11c 100644 --- a/src/SolARCameraOpencv.cpp +++ b/src/SolARCameraOpencv.cpp @@ -68,7 +68,7 @@ namespace OPENCV { auto setResolution = [&] (cv::VideoCaptureProperties dimensionProp, uint32_t value, - std::string dimensionName) + const std::string& dimensionName) { bool setResDimOk = m_capture.set(dimensionProp, value); diff --git a/src/SolARImagesAsCameraOpencv.cpp b/src/SolARImagesAsCameraOpencv.cpp index 4f790a6b..49fed68f 100644 --- a/src/SolARImagesAsCameraOpencv.cpp +++ b/src/SolARImagesAsCameraOpencv.cpp @@ -68,7 +68,7 @@ namespace OPENCV { auto setResolution = [&] (cv::VideoCaptureProperties dimensionProp, uint32_t value, - std::string dimensionName) + const std::string& dimensionName) { bool setResDimOk = m_capture.set(dimensionProp, value); diff --git a/src/SolARVideoAsCameraOpencv.cpp b/src/SolARVideoAsCameraOpencv.cpp index 28270296..a3492671 100644 --- a/src/SolARVideoAsCameraOpencv.cpp +++ b/src/SolARVideoAsCameraOpencv.cpp @@ -71,7 +71,7 @@ using namespace datastructure; auto setResolution = [&] (cv::VideoCaptureProperties dimensionProp, uint32_t value, - std::string dimensionName) + const std::string& dimensionName) { bool setResDimOk = m_capture.set(dimensionProp, value);