@@ -12,24 +12,29 @@ def drawFeatures(frame, features):
12
12
for feature in features :
13
13
# descriptor = feature.descriptor
14
14
# print(descriptor)
15
- if feature .age < 2 :
16
- cv2 .circle (frame , (int (feature .position .x ), int (feature .position .y )), circleRadius , greenColor , - 1 , cv2 .LINE_AA , 0 )
17
- else :
15
+ if feature .age > 2 :
18
16
cv2 .circle (frame , (int (feature .position .x ), int (feature .position .y )), circleRadius , pointColor , - 1 , cv2 .LINE_AA , 0 )
17
+ # elif feature.age < 255:
18
+ # cv2.circle(frame, (int(feature.position.x), int(feature.position.y)), circleRadius, (0, 0, feature.age), -1, cv2.LINE_AA, 0)
19
+ else :
20
+ cv2 .circle (frame , (int (feature .position .x ), int (feature .position .y )), circleRadius , greenColor , - 1 , cv2 .LINE_AA , 0 )
19
21
20
22
class HostCamera (dai .node .ThreadedHostNode ):
21
23
def __init__ (self ):
22
24
dai .node .ThreadedHostNode .__init__ (self )
23
25
self .output = dai .Node .Output (self )
24
26
def run (self ):
25
27
# Create a VideoCapture object
26
- cap = cv2 .VideoCapture (0 )
28
+ cap = cv2 .VideoCapture ("/home/nebojsa/Documents/depthai-device-kb/external/depthai-core/examples/python/models/construction_vest.mp4" )
29
+ # cap = cv2.VideoCapture(0)
27
30
if not cap .isOpened ():
28
31
pipeline .stop ()
29
32
raise RuntimeError ("Error: Couldn't open host camera" )
30
33
while self .isRunning ():
31
34
# frame = depthImg
32
35
ret , frame = cap .read ()
36
+ # frame = cv2.imread("/home/nebojsa/Downloads/image.jpg")
37
+ frame = cv2 .resize (frame , (640 , 640 ), interpolation = cv2 .INTER_LINEAR )
33
38
frame = cv2 .cvtColor (frame , cv2 .COLOR_BGR2GRAY )
34
39
imgFrame = dai .ImgFrame ()
35
40
imgFrame .setData (frame )
@@ -52,12 +57,15 @@ def run(self):
52
57
initialRobustness = 100
53
58
54
59
def on_trackbar (val ):
55
- cfg = dai .FeatureTrackerConfigRvc4 ()
60
+ cfg = dai .FeatureTrackerConfig ()
61
+ cornerDetector = dai .FeatureTrackerConfig .CornerDetector ()
62
+ cornerDetector .numMaxFeatures = cv2 .getTrackbarPos ('numMaxFeatures' , 'Features' )
56
63
57
- cfg . setHarrisCornerDetectorThreshold ( cv2 . getTrackbarPos ( 'harris_score' , 'Features' ) )
58
- cfg . setHarrisCornerDetectorRobustness ( cv2 .getTrackbarPos ('robustness ' ,'Features' ) )
59
- cfg . setNumMaxFeatures ( cv2 . getTrackbarPos ( 'numMaxFeatures' , 'Features' ))
64
+ thresholds = dai . FeatureTrackerConfig . CornerDetector . Thresholds ( )
65
+ thresholds . initialValue = cv2 .getTrackbarPos ('harris_score ' ,'Features' )
66
+ cornerDetector . thresholds = thresholds
60
67
68
+ cfg .setCornerDetector (cornerDetector )
61
69
cfg .setMotionEstimator (motionEstimator )
62
70
63
71
inputConfigQueue .send (cfg )
@@ -67,7 +75,7 @@ def on_trackbar(val):
67
75
68
76
# create trackbars threshold and robustness change
69
77
cv2 .createTrackbar ('harris_score' ,'Features' ,2000 ,25000 , on_trackbar )
70
- cv2 .createTrackbar ('robustness' ,'Features' ,100 ,127 , on_trackbar )
78
+ # cv2.createTrackbar('robustness','Features',100,127, on_trackbar)
71
79
cv2 .createTrackbar ('numMaxFeatures' ,'Features' ,256 ,1024 , on_trackbar )
72
80
73
81
@@ -77,12 +85,24 @@ def on_trackbar(val):
77
85
hostCamera = pipeline .create (HostCamera )
78
86
camQueue = hostCamera .output .createOutputQueue ()
79
87
80
- featureTrackerLeft = pipeline .create (dai .node .FeatureTrackerRvc4 )
88
+ featureTrackerLeft = pipeline .create (dai .node .FeatureTracker )
81
89
82
- featureTrackerLeft .initialConfig .setHarrisCornerDetectorThreshold (initialThreshold )
83
- featureTrackerLeft .initialConfig .setHarrisCornerDetectorRobustness (initialRobustness )
84
- featureTrackerLeft .initialConfig .setCornerDetector (dai .FeatureTrackerConfigRvc4 .CornerDetector .Type .HARRIS )
85
- featureTrackerLeft .initialConfig .setNumMaxFeatures (256 )
90
+ # featureTrackerLeft.initialConfig.setHarrisCornerDetectorThreshold(initialThreshold)
91
+ # featureTrackerLeft.initialConfig.setHarrisCornerDetectorRobustness(initialRobustness)
92
+ featureTrackerLeft .initialConfig .setCornerDetector (dai .FeatureTrackerConfig .CornerDetector .Type .HARRIS )
93
+ featureTrackerLeft .initialConfig .setMotionEstimator (False )
94
+
95
+ motionEstimator = dai .FeatureTrackerConfig .MotionEstimator ()
96
+ motionEstimator .enable = True
97
+ featureTrackerLeft .initialConfig .setMotionEstimator (motionEstimator )
98
+
99
+ cornerDetector = dai .FeatureTrackerConfig .CornerDetector ()
100
+ cornerDetector .numMaxFeatures = 256
101
+
102
+
103
+
104
+
105
+ # featureTrackerLeft.initialConfig.setNumMaxFeatures(256)
86
106
87
107
88
108
outputFeaturePassthroughQueue = featureTrackerLeft .passthroughInputImage .createOutputQueue ()
@@ -91,10 +111,12 @@ def on_trackbar(val):
91
111
hostCamera .output .link (featureTrackerLeft .inputImage )
92
112
93
113
inputConfigQueue = featureTrackerLeft .inputConfig .createInputQueue ()
94
- motionEstimator = dai .FeatureTrackerConfigRvc4 .MotionEstimator ()
95
- motionEstimator .enable = False
96
114
97
- thresholds = dai .FeatureTrackerConfigRvc4 .CornerDetector .Thresholds ()
115
+ thresholds = dai .FeatureTrackerConfig .CornerDetector .Thresholds ()
116
+ thresholds .initialValue = cv2 .getTrackbarPos ('harris_score' ,'Features' )
117
+
118
+ cornerDetector .thresholds = thresholds
119
+ featureTrackerLeft .initialConfig .setCornerDetector (cornerDetector )
98
120
99
121
pipeline .start ()
100
122
while pipeline .isRunning ():
@@ -118,10 +140,17 @@ def on_trackbar(val):
118
140
if key == ord ('q' ):
119
141
break
120
142
elif key == ord ('m' ):
121
- cfg = dai .FeatureTrackerConfigRvc4 ()
122
- cfg .setHarrisCornerDetectorThreshold (cv2 .getTrackbarPos ('harris_score' ,'Features' ))
123
- cfg .setHarrisCornerDetectorRobustness (cv2 .getTrackbarPos ('robustness' ,'Features' ))
124
- cfg .setNumMaxFeatures (cv2 .getTrackbarPos ('numMaxFeatures' , 'Features' ))
143
+ cfg = dai .FeatureTrackerConfig ()
144
+ cornerDetector = dai .FeatureTrackerConfig .CornerDetector ()
145
+ cornerDetector .numMaxFeatures = cv2 .getTrackbarPos ('numMaxFeatures' , 'Features' )
146
+
147
+ thresholds = dai .FeatureTrackerConfig .CornerDetector .Thresholds ()
148
+ thresholds .initialValue = cv2 .getTrackbarPos ('harris_score' ,'Features' )
149
+ cornerDetector .thresholds = thresholds
150
+
151
+ cfg .setCornerDetector (cornerDetector )
152
+ cfg .setMotionEstimator (motionEstimator )
153
+
125
154
if motionEstimator .enable == False :
126
155
motionEstimator .enable = True
127
156
cfg .setMotionEstimator (motionEstimator )
0 commit comments