1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
|
Index: include/calibration/ArucoDetector.h
===================================================================
--- include/calibration/ArucoDetector.h (Revision 2403)
+++ include/calibration/ArucoDetector.h (Arbeitskopie)
@@ -27,8 +27,8 @@
private:
std::vector<AprilTag::AprilTag3f> _patternPoints;
std::string _dictionaryName;
- cv::Ptr<cv::aruco::Dictionary> _dictionary;
- cv::Ptr<cv::aruco::DetectorParameters> _detectorParams;
+ cv::aruco::Dictionary _dictionary;
+ cv::aruco::DetectorParameters _detectorParams;
std::vector<AprilTag::AprilTag2f> _tags;
};
Index: include/scanio/helper.h
===================================================================
--- include/scanio/helper.h (Revision 2403)
+++ include/scanio/helper.h (Arbeitskopie)
@@ -5,6 +5,7 @@
#include <iostream>
#include <string>
#include <sstream>
+#include <list>
#include "slam6d/pointfilter.h"
#include "slam6d/io_types.h"
#include "slam6d/scan_settings.h"
Index: src/calibration/ArucoDetector.cc
===================================================================
--- src/calibration/ArucoDetector.cc (Revision 2403)
+++ src/calibration/ArucoDetector.cc (Arbeitskopie)
@@ -20,8 +20,8 @@
throw(std::invalid_argument("unrecognized dictionary name, only DICT_6X6_250 and DICT_APRILTAG_36h11 are supported!"));
}
- _detectorParams = cv::aruco::DetectorParameters::create();
- _detectorParams->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
+ _detectorParams = cv::aruco::DetectorParameters();
+ _detectorParams.cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
}
ArucoDetector::~ArucoDetector()
@@ -42,7 +42,7 @@
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f> > markerCorners;
- cv::aruco::detectMarkers(gray, _dictionary, markerCorners, markerIds, _detectorParams);
+ cv::aruco::detectMarkers(gray, &_dictionary, markerCorners, markerIds, &_detectorParams);
for (size_t i = 0; i < markerIds.size(); i++) {
AprilTag::AprilTag2f aprilTag2f = AprilTag::AprilTag2f(markerIds.at(i));
Index: src/slam6d/fbr/feature.cc
===================================================================
--- src/slam6d/fbr/feature.cc (Revision 2403)
+++ src/slam6d/fbr/feature.cc (Arbeitskopie)
@@ -60,7 +60,7 @@
//Detect the keypoints using SIFT Detector
case SIFT_DET:{
#if (CV_MAJOR_VERSION >= 3) && (CV_MINOR_VERSION >= 0)
- Ptr<xfeatures2d::SIFT> detector = xfeatures2d::SIFT::create();
+ Ptr<cv::SIFT> detector = cv::SIFT::create();
detector->detect(pImage, keypoints, descriptors);
#else
cv::SiftFeatureDetector detector;
@@ -159,7 +159,7 @@
case SIFT_DES:{
//Create descriptor using SIFT
#if (CV_MAJOR_VERSION >= 3) && (CV_MINOR_VERSION >= 0)
- Ptr<xfeatures2d::SIFT> extractor = xfeatures2d::SIFT::create();
+ Ptr<cv::SIFT> extractor = cv::SIFT::create();
extractor->compute(pImage, keypoints, descriptors);
#else
cv::SiftDescriptorExtractor extractor;
|