Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
vision_utils
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
labrobotica
algorithms
vision_utils
Commits
0b04de56
Commit
0b04de56
authored
7 years ago
by
Angel Santamaria-Navarro
Browse files
Options
Downloads
Patches
Plain Diff
FIX: fundamental_matrix example
parent
97281eda
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
src/examples/fundamental_matrix.cpp
+80
-23
80 additions, 23 deletions
src/examples/fundamental_matrix.cpp
src/examples/yaml/fundamental_matrix.yaml
+23
-0
23 additions, 0 deletions
src/examples/yaml/fundamental_matrix.yaml
with
103 additions
and
23 deletions
src/examples/fundamental_matrix.cpp
+
80
−
23
View file @
0b04de56
...
...
@@ -33,7 +33,7 @@ int main(int argc, char** argv)
cv
::
VideoCapture
capture
;
if
(
argc
<
2
)
{
std
::
cout
<<
"Please use
\n\t
./
test_opencv
<arg> "
std
::
cout
<<
"Please use
\n\t
./
fundamental_matrix
<arg> "
"
\n
with "
"
\n\t
arg = <path/videoname.mp4> for video input "
"
\n\t
arg = 0 for camera input."
<<
std
::
endl
;
...
...
@@ -58,23 +58,81 @@ int main(int argc, char** argv)
else
std
::
cout
<<
"succeded"
<<
std
::
endl
;
// set image detector
vision_utils
::
DetectorParamsORBPtr
det_params
=
std
::
make_shared
<
vision_utils
::
DetectorParamsORB
>
();
vision_utils
::
DetectorBasePtr
det_b_ptr
=
vision_utils
::
setupDetector
(
"ORB"
,
"ORB detector"
,
det_params
);
vision_utils
::
DetectorORBPtr
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorORB
>
(
det_b_ptr
);
// set image descriptor
vision_utils
::
DescriptorParamsORBPtr
desc_params
=
std
::
make_shared
<
vision_utils
::
DescriptorParamsORB
>
();
vision_utils
::
DescriptorBasePtr
des_b_ptr
=
vision_utils
::
setupDescriptor
(
"ORB"
,
"ORB detector"
,
desc_params
);
vision_utils
::
DescriptorORBPtr
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorORB
>
(
des_b_ptr
);
// set matcher
std
::
string
matcher_name
=
"BRUTEFORCE_HAMMING_2"
;
vision_utils
::
MatcherParamsBasePtr
mat_params
=
std
::
make_shared
<
vision_utils
::
MatcherParamsBase
>
(
matcher_name
);
mat_params
->
match_type
=
vision_utils
::
MATCH
;
vision_utils
::
MatcherBasePtr
mat_b_ptr
=
vision_utils
::
setupMatcher
(
matcher_name
,
matcher_name
,
mat_params
);
vision_utils
::
MatcherBRUTEFORCE_HAMMING_2Ptr
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherBRUTEFORCE_HAMMING_2
>
(
mat_b_ptr
);
// YAML file with parameters
std
::
string
path_yaml_file
=
"/src/examples/yaml"
;
std
::
string
vu_root
=
_VU_ROOT_DIR
;
// Root dir path
std
::
string
yaml_file_params_vision_utils
=
vu_root
+
path_yaml_file
+
"/fundamental_matrix.yaml"
;
// Detector
std
::
string
det_name
=
vision_utils
::
readYamlType
(
yaml_file_params_vision_utils
,
"detector"
);
vision_utils
::
DetectorBasePtr
det_ptr
=
vision_utils
::
setupDetector
(
det_name
,
det_name
+
" detector"
,
yaml_file_params_vision_utils
);
if
(
det_name
.
compare
(
"ORB"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorORB
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"FAST"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorFAST
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"SIFT"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorSIFT
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"SURF"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorSURF
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"BRISK"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorBRISK
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"MSER"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorMSER
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"GFTT"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorGFTT
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"HARRIS"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorHARRIS
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"SBD"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorSBD
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"KAZE"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorKAZE
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"AKAZE"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorAKAZE
>
(
det_ptr
);
else
if
(
det_name
.
compare
(
"AGAST"
)
==
0
)
det_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DetectorAGAST
>
(
det_ptr
);
// Descriptor
std
::
string
des_name
=
vision_utils
::
readYamlType
(
yaml_file_params_vision_utils
,
"descriptor"
);
vision_utils
::
DescriptorBasePtr
des_ptr
=
vision_utils
::
setupDescriptor
(
des_name
,
des_name
+
" descriptor"
,
yaml_file_params_vision_utils
);
if
(
des_name
.
compare
(
"ORB"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorORB
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"SIFT"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorSIFT
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"SURF"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorSURF
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"BRISK"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorBRISK
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"KAZE"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorKAZE
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"AKAZE"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorAKAZE
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"LATCH"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorLATCH
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"FREAK"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorFREAK
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"BRIEF"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorBRIEF
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"DAISY"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorDAISY
>
(
des_ptr
);
else
if
(
des_name
.
compare
(
"LUCID"
)
==
0
)
des_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
DescriptorLUCID
>
(
des_ptr
);
// Matcher
std
::
string
mat_name
=
vision_utils
::
readYamlType
(
yaml_file_params_vision_utils
,
"matcher"
);
vision_utils
::
MatcherBasePtr
mat_ptr
=
vision_utils
::
setupMatcher
(
mat_name
,
mat_name
+
" matcher"
,
yaml_file_params_vision_utils
);
if
(
mat_name
.
compare
(
"FLANNBASED"
)
==
0
)
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherFLANNBASED
>
(
mat_ptr
);
if
(
mat_name
.
compare
(
"BRUTEFORCE"
)
==
0
)
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherBRUTEFORCE
>
(
mat_ptr
);
if
(
mat_name
.
compare
(
"BRUTEFORCE_L1"
)
==
0
)
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherBRUTEFORCE_L1
>
(
mat_ptr
);
if
(
mat_name
.
compare
(
"BRUTEFORCE_HAMMING"
)
==
0
)
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherBRUTEFORCE_HAMMING
>
(
mat_ptr
);
if
(
mat_name
.
compare
(
"BRUTEFORCE_HAMMING_2"
)
==
0
)
mat_ptr
=
std
::
static_pointer_cast
<
vision_utils
::
MatcherBRUTEFORCE_HAMMING_2
>
(
mat_ptr
);
// set and print image properties
unsigned
int
img_width
=
(
unsigned
int
)
capture
.
get
(
CV_CAP_PROP_FRAME_WIDTH
);
...
...
@@ -91,7 +149,6 @@ int main(int argc, char** argv)
cv
::
namedWindow
(
"Feature tracker"
);
// Creates a window for display.
cv
::
moveWindow
(
"Feature tracker"
,
0
,
0
);
// First image
KeyPointVector
keypoints_1
=
det_ptr
->
detect
(
image_buffer
.
back
());
cv
::
Mat
descriptors_1
=
des_ptr
->
getDescriptor
(
image_buffer
.
back
(),
keypoints_1
);
...
...
@@ -117,7 +174,7 @@ int main(int argc, char** argv)
{
image_buffer
.
add
(
img
);
cv
::
Mat
descriptors_2
=
des_ptr
->
getDescriptor
(
image_buffer
.
back
(),
keypoints_
1
);
cv
::
Mat
descriptors_2
=
des_ptr
->
getDescriptor
(
image_buffer
.
back
(),
keypoints_
2
);
unsigned
int
max_dist
=
0
;
unsigned
int
min_dist
=
512
;
...
...
@@ -175,13 +232,13 @@ int main(int argc, char** argv)
std
::
cout
<<
"Matches: initial "
<<
matches
.
size
()
<<
" | good "
<<
good_matches
.
size
()
<<
" | inliers "
<<
inlier_matches
.
size
()
<<
std
::
endl
;
std
::
cout
<<
"+++++++++++++++"
<<
std
::
endl
;
std
::
cout
<<
keypoints_1
.
size
()
<<
" "
<<
keypoints_2
.
size
()
<<
" "
<<
inlier_matches
.
size
()
<<
" "
<<
img_matches
.
size
()
<<
std
::
endl
;
std
::
cout
<<
"kp1: "
<<
keypoints_1
.
size
()
<<
" kp2: "
<<
keypoints_2
.
size
()
<<
" inliers:"
<<
inlier_matches
.
size
()
<<
std
::
endl
;
std
::
cout
<<
"+++++++++++++++"
<<
std
::
endl
;
// Draw RANSAC inliers
cv
::
drawMatches
(
image_buffer
[
image_buffer
.
size
()
-
2
],
keypoints_1
,
image_buffer
.
back
(),
keypoints_2
,
inlier_matches
,
img_matches
,
cv
::
Scalar
::
all
(
-
1
),
cv
::
Scalar
::
all
(
-
1
),
std
::
vector
<
char
>
(),
0
);
//cv::DrawMatchesFlags::NOT_DRAW_SINGLE_POINTS );
cv
::
Scalar
::
all
(
-
1
),
cv
::
Scalar
::
all
(
-
1
),
std
::
vector
<
char
>
(),
0
);
//cv::DrawMatchesFlags::NOT_DRAW_SINGLE_POINTS );
// Show detected matches
imshow
(
"Feature tracker"
,
img_matches
);
...
...
This diff is collapsed.
Click to expand it.
src/examples/yaml/fundamental_matrix.yaml
0 → 100644
+
23
−
0
View file @
0b04de56
detector
:
type
:
"
GFTT"
maxCorners
:
1000
qualityLevel
:
0.015
minDistance
:
20.0
blockSize
:
15
k
:
0.04
descriptor
:
type
:
"
ORB"
nfeatures
:
1000
scale factor
:
1.2
nlevels
:
8
edge threshold
:
31
# 16
first level
:
0
WTA_K
:
2
# See: http://docs.opencv.org/trunk/db/d95/classcv_1_1ORB.html#a180ae17d3300cf2c619aa240d9b607e5
score type
:
1
#enum { kBytes = 32, HARRIS_SCORE=0, FAST_SCORE=1 };
patch size
:
31
# 31
matcher
:
type
:
"
BRUTEFORCE"
# BRUTEFORCE, BRUTEFORCE_HAMMING, BRUTEFORCE_HAMMING_2, BRUTEFORCE_L1, FLANNBASED
match type
:
1
# Match type. MATCH = 1, KNNMATCH = 2, RADIUSMATCH = 3
min normalized score
:
0.8
\ No newline at end of file
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment