summarylogtreecommitdiffstats
path: root/cv4-8.patch
blob: 8918199feeab6e91b14ec8f41ad8e9208e0edb1d (plain)
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
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
Index: include/calibration/ArucoDetector.h
===================================================================
--- include/calibration/ArucoDetector.h	(Revision 2390)
+++ include/calibration/ArucoDetector.h	(Arbeitskopie)
@@ -2,6 +2,7 @@
 #define CALIBRATION_ARUCODETECTOR_H
 
 #include "opencv2/core/version.hpp"
+#include <opencv2/objdetect/aruco_dictionary.hpp>
 
 #if CV_MAJOR_VERSION > 3
 
@@ -27,8 +28,13 @@
 private:
     std::vector<AprilTag::AprilTag3f> _patternPoints;
     std::string _dictionaryName;
+#if (CV_MAJOR_VERSION >= 4)
+    cv::aruco::Dictionary _dictionary;
+    cv::aruco::DetectorParameters _detectorParams;
+#else
     cv::Ptr<cv::aruco::Dictionary> _dictionary;
     cv::Ptr<cv::aruco::DetectorParameters> _detectorParams;
+#endif
     std::vector<AprilTag::AprilTag2f> _tags;
 };
 
Index: src/calibration/ArucoDetector.cc
===================================================================
--- src/calibration/ArucoDetector.cc	(Revision 2390)
+++ src/calibration/ArucoDetector.cc	(Arbeitskopie)
@@ -1,5 +1,6 @@
 #include "calibration/ArucoDetector.h"
 #include <chrono>
+#include <opencv2/objdetect/aruco_detector.hpp>
 #include <opencv2/opencv.hpp>
 #include <boost/filesystem.hpp>
 #include <calibration/DetectionFileHandler.h>
@@ -20,8 +21,14 @@
         throw(std::invalid_argument("unrecognized dictionary name, only DICT_6X6_250 and DICT_APRILTAG_36h11 are supported!"));
     }
 
+#if (CV_MAJOR_VERSION >= 4)
+    _detectorParams = cv::aruco::DetectorParameters();
+    _detectorParams.cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
+#else
     _detectorParams = cv::aruco::DetectorParameters::create();
     _detectorParams->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
+#endif
+    
 }
 
 ArucoDetector::~ArucoDetector()
@@ -42,7 +49,11 @@
 
     std::vector<int> markerIds;
     std::vector<std::vector<cv::Point2f> > markerCorners;
+#if (CV_MAJOR_VERSION >= 4)
+    cv::aruco::detectMarkers(gray, &_dictionary, markerCorners, markerIds, &_detectorParams);
+#else
     cv::aruco::detectMarkers(gray, _dictionary, markerCorners, markerIds, _detectorParams);
+#endif
 
     for (size_t i = 0; i < markerIds.size(); i++) {
         AprilTag::AprilTag2f aprilTag2f = AprilTag::AprilTag2f(markerIds.at(i));
Index: src/scanserver/frame_io.cc
===================================================================
--- src/scanserver/frame_io.cc	(Revision 2390)
+++ src/scanserver/frame_io.cc	(Arbeitskopie)
@@ -9,6 +9,7 @@
 
 #include "scanserver/frame_io.h"
 
+#include <sstream>
 #include <vector>
 
 #include <boost/filesystem/operations.hpp>
Index: src/slam6d/fbr/feature.cc
===================================================================
--- src/slam6d/fbr/feature.cc	(Revision 2390)
+++ src/slam6d/fbr/feature.cc	(Arbeitskopie)
@@ -60,7 +60,11 @@
               //Detect the keypoints using SIFT Detector
             case SIFT_DET:{
 #if (CV_MAJOR_VERSION >= 3) && (CV_MINOR_VERSION >= 0)
+    #if (CV_MAJOR_VERSION >= 4)
+              Ptr<cv::SIFT> detector = cv::SIFT::create();
+    #else
               Ptr<xfeatures2d::SIFT> detector = xfeatures2d::SIFT::create();
+    #endif
               detector->detect(pImage, keypoints, descriptors);
 #else
               cv::SiftFeatureDetector detector;
@@ -159,7 +163,11 @@
             case SIFT_DES:{
               //Create descriptor using SIFT
 #if (CV_MAJOR_VERSION >= 3) && (CV_MINOR_VERSION >= 0)
+    #if (CV_MAJOR_VERSION >= 4)
+              Ptr<cv::SIFT> extractor = cv::SIFT::create();
+    #else
               Ptr<xfeatures2d::SIFT> extractor = xfeatures2d::SIFT::create();
+    #endif
               extractor->compute(pImage, keypoints, descriptors);
 #else
               cv::SiftDescriptorExtractor extractor;
Index: src/slam6d/scan2features.cc
===================================================================
--- src/slam6d/scan2features.cc	(Revision 2390)
+++ src/slam6d/scan2features.cc	(Arbeitskopie)
@@ -27,6 +27,7 @@
 #include "newmat/newmat.h"
 #include "newmat/newmatap.h"
 
+#include <cfloat>
 #include <csignal>
 
 #ifdef _MSC_VER