Skip to content
This repository was archived by the owner on Jul 20, 2023. It is now read-only.

Commit e812dbf

Browse files
committed
Merge branch 'develop'
2 parents 9695a5b + d6bda89 commit e812dbf

File tree

67 files changed

+1194
-403
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

67 files changed

+1194
-403
lines changed

.gitignore

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -55,8 +55,10 @@ Release/
5555
*-packagedependencies-unix.*
5656
*-packagedependencies-android.*
5757
*.pc
58-
*-Debug
59-
*-Release
58+
*-Debug*
59+
*-Release*
60+
*_Debug*
61+
*_Release*
6062

6163
# Executables
6264
*.exe

SolARModuleOpenCV.pri

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ HEADERS += interfaces/SolAR2D3DcorrespondencesFinderOpencv.h \
66
interfaces/SolARCameraOpencv.h \
77
interfaces/SolARContoursExtractorOpencv.h \
88
interfaces/SolARContoursFilterBinaryMarkerOpencv.h \
9+
interfaces/SolARCornerRefinementOpencv.h \
910
interfaces/SolARDescriptorMatcherHammingBruteForceOpencv.h \
1011
interfaces/SolARDescriptorMatcherKNNOpencv.h \
1112
interfaces/SolARDescriptorMatcherRadiusOpencv.h \
@@ -70,6 +71,7 @@ SOURCES += src/AKAZE2/akaze.cpp \
7071
src/SolARCameraOpencv.cpp \
7172
src/SolARContoursExtractorOpencv.cpp \
7273
src/SolARContoursFilterBinaryMarkerOpencv.cpp \
74+
src/SolARCornerRefinementOpencv.cpp \
7375
src/SolARDescriptorMatcherHammingBruteForceOpencv.cpp \
7476
src/SolARDescriptorMatcherKNNOpencv.cpp \
7577
src/SolARDescriptorMatcherRadiusOpencv.cpp \

SolARModuleOpenCV.pro

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ CONFIG -= qt
66
INSTALLSUBDIR = SolARBuild
77
TARGET = SolARModuleOpenCV
88
FRAMEWORK = $$TARGET
9-
VERSION=0.9.0
9+
VERSION=0.9.1
1010

1111
DEFINES += MYVERSION=$${VERSION}
1212
DEFINES += TEMPLATE_LIBRARY

bcom-SolARModuleOpenCV.pc.in

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ libdir=${exec_prefix}/lib
55
includedir=${prefix}/interfaces
66
Name: SolARModuleOpenCV
77
Description:
8-
Version: 0.9.0
8+
Version: 0.9.1
99
Requires:
1010
Libs: -L${libdir} -l${libname}
1111
Libs.private: ${libdir}/${pfx}${libname}.${lext}
Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
/**
2+
* @copyright Copyright (c) 2017 B-com http://www.b-com.com/
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*/
16+
17+
#ifndef SOLARCORNERREFINEMENTOPENCV_H
18+
#define SOLARCORNERREFINEMENTOPENCV_H
19+
20+
#include "xpcf/component/ConfigurableBase.h"
21+
#include "SolAROpencvAPI.h"
22+
#include "api/features/ICornerRefinement.h"
23+
#include "opencv2/core.hpp"
24+
#include <vector>
25+
26+
namespace SolAR {
27+
namespace MODULES {
28+
namespace OPENCV {
29+
30+
/**
31+
* @class SolARCornerRefinementOpencv
32+
* @brief <B>Refine the corner locations.</B>
33+
* <TT>UUID: ddae46ca-1657-4301-a87d-f2dcfa6265d0</TT>
34+
*
35+
*/
36+
37+
class SOLAROPENCV_EXPORT_API SolARCornerRefinementOpencv : public org::bcom::xpcf::ConfigurableBase,
38+
public api::features::ICornerRefinement
39+
{
40+
public:
41+
/// @brief SolARCornerRefinementOpencv constructor
42+
SolARCornerRefinementOpencv();
43+
44+
/// @brief SolARCornerRefinementOpencv default destructor
45+
~SolARCornerRefinementOpencv() = default;
46+
47+
/// @brief This method refines the corner locations
48+
/// @param[in] image Input image on which we are extracting keypoints.
49+
/// @param[in,out] corners Initial coordinates of the input corners and refined coordinates provided for output.
50+
void refine(const SRef<datastructure::Image> image, std::vector<datastructure::Point2Df> & corners) override;
51+
52+
org::bcom::xpcf::XPCFErrorCode onConfigured() override final;
53+
54+
void unloadComponent () override final;
55+
56+
private:
57+
uint32_t m_nbMaxIters = 40;
58+
float m_minAccuracy = 0.01;
59+
cv::TermCriteria m_termcrit;
60+
uint32_t m_winSize = 5;
61+
cv::Size m_subPixWinSize;
62+
};
63+
64+
}
65+
}
66+
}
67+
68+
#endif // SOLARCORNERREFINEMENTOPENCV_H

interfaces/SolARDescriptorMatcherKNNOpencv.h

Lines changed: 22 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -72,15 +72,15 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom:
7272
/// [in] desc2: target descriptor.
7373
/// [out] matches: ensemble of detected matches, a pair of source/target indices.
7474
///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed.
75-
IDescriptorMatcher::RetCode match(
75+
IDescriptorMatcher::RetCode match(
7676
const SRef<datastructure::DescriptorBuffer> desc1,
7777
const SRef<datastructure::DescriptorBuffer> desc2,
7878
std::vector<datastructure::DescriptorMatch> & matches) override;
79-
/// @brief Matches a descriptor desc1 with an ensemble of descriptors desc2 based on KNN search strategy.
80-
/// [in] desc1: source descriptor.
81-
/// [in] desc2: target descriptors.
82-
/// [out] matches: ensemble of detected matches, a pair of source/target indices.
83-
///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed.
79+
/// @brief Matches a descriptor desc1 with an ensemble of descriptors desc2 based on KNN search strategy.
80+
/// [in] desc1: source descriptor.
81+
/// [in] desc2: target descriptors.
82+
/// [out] matches: ensemble of detected matches, a pair of source/target indices.
83+
///@return IDescriptorMatcher::RetCode::DESCRIPTORS_MATCHER_OK if succeed.
8484
IDescriptorMatcher::RetCode match(
8585
const SRef<datastructure::DescriptorBuffer> descriptors1,
8686
const std::vector<SRef<datastructure::DescriptorBuffer>> & descriptors2,
@@ -92,7 +92,7 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom:
9292
/// @param[in] frame The frame contains descriptors to match.
9393
/// @param[out] matches A vector of matches representing pairs of indices relatively to the first and second set of descriptors.
9494
/// @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.
95-
virtual IDescriptorMatcher::RetCode matchInRegion(
95+
IDescriptorMatcher::RetCode matchInRegion(
9696
const std::vector<datastructure::Point2Df> & points2D,
9797
const std::vector<SRef<datastructure::DescriptorBuffer>> & descriptors,
9898
const SRef<datastructure::Frame> frame,
@@ -101,6 +101,21 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom:
101101
const float matchingDistanceMax = 0.f
102102
) override;
103103

104+
/// @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
105+
/// @param[in] currentFrame the current frame.
106+
/// @param[in] lastFrame the last frame.
107+
/// @param[out] matches a vector of matches between two frames representing pairs of keypoint indices relatively.
108+
/// @param[in] radius the radius of search region around each keypoint of the last frame.
109+
/// @param[in] matchingDistanceMax the maximum distance to valid a match.
110+
/// @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.
111+
IDescriptorMatcher::RetCode matchInRegion(
112+
const SRef<datastructure::Frame> currentFrame,
113+
const SRef<datastructure::Frame> lastFrame,
114+
std::vector<datastructure::DescriptorMatch> &matches,
115+
const float radius = 0.f,
116+
const float matchingDistanceMax = 0.f
117+
) override;
118+
104119

105120
private:
106121

@@ -116,11 +131,6 @@ class SOLAROPENCV_EXPORT_API SolARDescriptorMatcherKNNOpencv : public org::bcom:
116131
int m_id;
117132
cv::FlannBasedMatcher m_matcher;
118133

119-
IDescriptorMatcher::RetCode match(
120-
SRef<datastructure::DescriptorBuffer>& descriptors1,
121-
SRef<datastructure::DescriptorBuffer>& descriptors2,
122-
std::vector<std::vector< cv::DMatch >>& matches,int nbOfMatches);
123-
124134
};
125135

126136
}

interfaces/SolARKeypointDetectorOpencv.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,9 @@ class SOLAROPENCV_EXPORT_API SolARKeypointDetectorOpencv : public org::bcom::xpc
105105
int m_id;
106106
cv::Ptr<cv::Feature2D> m_detector;
107107
cv::KeyPointsFilter kptsFilter;
108+
int m_nbGridWidth = 20;
109+
int m_nbGridHeight = 20;
110+
float m_borderRatio = 0.01f;
108111

109112
};
110113

interfaces/SolARModuleOpencv_traits.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,7 @@ class SolARUndistortPointsOpencv;
7777
class SolARVideoAsCameraOpencv;
7878
class SolARDeviceDataLoader;
7979
class SolARMapFusionOpencv;
80+
class SolARCornerRefinementOpencv;
8081
}
8182
}
8283
}
@@ -324,5 +325,9 @@ XPCF_DEFINE_COMPONENT_TRAITS(SolAR::MODULES::OPENCV::SolARMapFusionOpencv,
324325
"bc661909-0185-40a4-a5e6-e52280e7b338",
325326
"SolARMapFusionOpencv",
326327
"Merge local map or floating map in the global map.")
328+
XPCF_DEFINE_COMPONENT_TRAITS(SolAR::MODULES::OPENCV::SolARCornerRefinementOpencv,
329+
"ddae46ca-1657-4301-a87d-f2dcfa6265d0",
330+
"SolARCornerRefinementOpencv",
331+
"Refine the corner locations.")
327332

328333
#endif // SOLARMODULEOPENCV_TRAITS_H

interfaces/SolARUndistortPointsOpencv.h

Lines changed: 20 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -16,15 +16,12 @@
1616

1717
#ifndef SOLARUNDISTORTPOINTS_H
1818
#define SOLARUNDISTORTPOINTS_H
19-
#include <vector>
2019

2120
#include "xpcf/component/ComponentBase.h"
2221
#include "SolAROpencvAPI.h"
2322
#include "api/geom/IUndistortPoints.h"
24-
2523
#include "opencv2/core.hpp"
26-
27-
#include "SolAROpencvAPI.h"
24+
#include <vector>
2825

2926
namespace SolAR {
3027
namespace MODULES {
@@ -45,12 +42,26 @@ class SOLAROPENCV_EXPORT_API SolARUndistortPointsOpencv : public org::bcom::xpcf
4542
~SolARUndistortPointsOpencv() = default;
4643

4744
void unloadComponent () override final;
48-
FrameworkReturnCode undistort(const std::vector<datastructure::Point2Df> & inputPoints, std::vector<datastructure::Point2Df> & outputPoints) override;
4945

50-
/// @brief Set the distortion intrinsic camera parameters
51-
void setDistortionParameters(const datastructure::CamDistortion & distortion_parameters) override;
52-
/// @brief Set the intrinsic camera parameters
53-
void setIntrinsicParameters(const datastructure::CamCalibration & intrinsic_parameters) override;
46+
/// @brief This method corrects undistortsion to a set of 2D points
47+
/// @param[in] inputPoints the set of 2D points to correct
48+
/// @param[out] outputPoints the undistorted 2D Points
49+
/// @return FrameworkReturnCode::_SUCCESS_ if 2D transformation succeed, else FrameworkReturnCode::_ERROR.
50+
FrameworkReturnCode undistort(const std::vector<datastructure::Point2Df> & inputPoints,
51+
std::vector<datastructure::Point2Df> & outputPoints) override;
52+
53+
/// @brief This method corrects undistortsion to a set of 2D keypoints
54+
/// @param[in] inputKeypoints the set of 2D keypoints to correct
55+
/// @param[out] outputKeypoints the undistorted 2D keypoints
56+
/// @return FrameworkReturnCode::_SUCCESS_ if 2D transformation succeed, else FrameworkReturnCode::_ERROR.
57+
FrameworkReturnCode undistort(const std::vector<datastructure::Keypoint> & inputKeypoints,
58+
std::vector<datastructure::Keypoint> & outputKeypoints) override;
59+
60+
/// @brief this method is used to set intrinsic parameters and distorsion of the camera
61+
/// @param[in] Camera calibration matrix parameters.
62+
/// @param[in] Camera distorsion parameters.
63+
void setCameraParameters(const datastructure::CamCalibration & intrinsicParams,
64+
const datastructure::CamDistortion & distorsionParams) override;
5465

5566

5667
private:

packagedependencies.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
SolARFramework|0.9.0|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download
1+
SolARFramework|0.9.1|SolARFramework|SolARBuild@github|https://github.com/SolarFramework/SolarFramework/releases/download

0 commit comments

Comments
 (0)