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
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
|
"""
This program is free software: you can redistribute it and/or modify it under
the terms of the GNU General Public License as published by the Free Software
Foundation, either version 3 of the License, or (at your option) any later
version.
This program is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with
this program. If not, see <http://www.gnu.org/licenses/>.
"""
__author__ = "Théo de la Hogue"
__credits__ = []
__copyright__ = "Copyright 2023, Ecole Nationale de l'Aviation Civile (ENAC)"
__license__ = "GPLv3"
from typing import Self
import json
import os
from collections import Counter
import time
from argaze import DataFeatures
from argaze.ArUcoMarkers import ArUcoMarkersDictionary, ArUcoMarker, ArUcoOpticCalibrator
import numpy
import cv2 as cv
from cv2 import aruco
class DetectorParameters():
"""Wrapper class around ArUco marker detector parameters.
!!! note
More details on [opencv page](https://docs.opencv.org/4.x/d1/dcd/structcv_1_1aruco_1_1DetectorParameters.html)
"""
__parameters = aruco.DetectorParameters()
__parameters_names = [
'adaptiveThreshConstant',
'adaptiveThreshWinSizeMax',
'adaptiveThreshWinSizeMin',
'adaptiveThreshWinSizeStep',
'aprilTagCriticalRad',
'aprilTagDeglitch',
'aprilTagMaxLineFitMse',
'aprilTagMaxNmaxima',
'aprilTagMinClusterPixels',
'aprilTagMinWhiteBlackDiff',
'aprilTagQuadDecimate',
'aprilTagQuadSigma',
'cornerRefinementMaxIterations',
'cornerRefinementMethod',
'cornerRefinementMinAccuracy',
'cornerRefinementWinSize',
'markerBorderBits',
'minMarkerPerimeterRate',
'maxMarkerPerimeterRate',
'minMarkerDistanceRate',
'detectInvertedMarker',
'errorCorrectionRate',
'maxErroneousBitsInBorderRate',
'minCornerDistanceRate',
'minDistanceToBorder',
'minOtsuStdDev',
'perspectiveRemoveIgnoredMarginPerCell',
'perspectiveRemovePixelPerCell',
'polygonalApproxAccuracyRate',
'useAruco3Detection'
]
def __init__(self, **kwargs):
for parameter, value in kwargs.items():
setattr(self.__parameters, parameter, value)
self.__dict__.update(kwargs)
def __setattr__(self, parameter, value):
setattr(self.__parameters, parameter, value)
def __getattr__(self, parameter):
return getattr(self.__parameters, parameter)
@classmethod
def from_json(self, json_filepath) -> Self:
"""Load detector parameters from .json file."""
with open(json_filepath) as configuration_file:
return DetectorParameters(**json.load(configuration_file))
def __str__(self) -> str:
"""Detector parameters string representation."""
return f'{self}'
def __format__(self, spec: str) -> str:
"""Formated detector parameters string representation.
Parameters:
spec: 'modified' to get only modified parameters.
"""
output = ''
for parameter in self.__parameters_names:
if parameter in self.__dict__.keys():
output += f'\t*{parameter}: {getattr(self.__parameters, parameter)}\n'
elif spec == "":
output += f'\t{parameter}: {getattr(self.__parameters, parameter)}\n'
return output
@property
def internal(self):
return self.__parameters
class ArUcoDetector(DataFeatures.PipelineStepObject):
"""OpenCV ArUco library wrapper."""
@DataFeatures.PipelineStepInit
def __init__(self, **kwargs):
"""Initialize ArUcoDetector."""
# Init private attributes
self.__dictionary = None
self.__optic_parameters = None
self.__parameters = None
# Init detected markers data
self.__detected_markers = {}
# Init detected board data
self.__board = None
self.__board_corners_number = 0
self.__board_corners = []
self.__board_corners_ids = []
@property
def dictionary(self) -> ArUcoMarkersDictionary.ArUcoMarkersDictionary:
"""ArUco markers dictionary to detect."""
return self.__dictionary
@dictionary.setter
@DataFeatures.PipelineStepAttributeSetter
def dictionary(self, dictionary: ArUcoMarkersDictionary.ArUcoMarkersDictionary):
self.__dictionary = dictionary
@property
def optic_parameters(self) -> ArUcoOpticCalibrator.OpticParameters:
"""Optic parameters to use for ArUco detection into image."""
return self.__optic_parameters
@optic_parameters.setter
@DataFeatures.PipelineStepAttributeSetter
def optic_parameters(self, optic_parameters: ArUcoOpticCalibrator.OpticParameters):
self.__optic_parameters = optic_parameters
@property
def parameters(self) -> DetectorParameters:
"""ArUco detector parameters."""
return self.__parameters
@parameters.setter
@DataFeatures.PipelineStepAttributeSetter
def parameters(self, parameters: DetectorParameters):
self.__parameters = parameters
@DataFeatures.PipelineStepMethod
def detect_markers(self, image: numpy.array):
"""Detect all ArUco markers into an image.
!!! danger "DON'T MIRROR IMAGE"
It makes the markers detection to fail.
!!! danger "DON'T UNDISTORED IMAGE"
Camera intrisic parameters and distorsion coefficients are used later during pose estimation.
"""
# Reset detected markers data
self.__detected_markers, detected_markers_corners, detected_markers_ids = {}, [], []
# Detect markers into gray picture
detected_markers_corners, detected_markers_ids, _ = aruco.detectMarkers(cv.cvtColor(image, cv.COLOR_BGR2GRAY), self.__dictionary.markers, parameters = self.__parameters.internal)
# Is there detected markers ?
if len(detected_markers_corners) > 0:
# Transform markers ids array into list
detected_markers_ids = detected_markers_ids.T[0]
for i, marker_id in enumerate(detected_markers_ids):
marker = ArUcoMarker.ArUcoMarker(self.__dictionary, marker_id)
marker.corners = detected_markers_corners[i][0]
# No pose estimation: call estimate_markers_pose to get one
marker.translation = numpy.empty([0])
marker.rotation = numpy.empty([0])
marker.points = numpy.empty([0])
self.__detected_markers[marker_id] = marker
def estimate_markers_pose(self, size: float, ids: list = []):
"""Estimate pose detected markers pose considering a marker size.
Parameters:
size: size of markers in centimeters.
ids: markers id list to select detected markers.
"""
# Is there detected markers ?
if len(self.__detected_markers) > 0:
# Select all markers by default
if len(ids) == 0:
ids = self.__detected_markers.keys()
# Prepare data for aruco.estimatePoseSingleMarkers function
selected_markers_corners = tuple()
selected_markers_ids = []
for marker_id, marker in self.__detected_markers.items():
if marker_id in ids:
selected_markers_corners += (marker.corners,)
selected_markers_ids.append(marker_id)
# Estimate pose of selected markers
if len(selected_markers_corners) > 0:
markers_rvecs, markers_tvecs, markers_points = aruco.estimatePoseSingleMarkers(selected_markers_corners, size, numpy.array(self.__optic_parameters.K), numpy.array(self.__optic_parameters.D))
for i, marker_id in enumerate(selected_markers_ids):
marker = self.__detected_markers[marker_id]
marker.translation = markers_tvecs[i][0]
marker.rotation, _ = cv.Rodrigues(markers_rvecs[i][0])
marker.size = size
marker.points = markers_points.reshape(4, 3).dot(marker.rotation) - marker.translation
def detected_markers(self) -> dict[ArUcoMarker.ArUcoMarker]:
"""Access to detected markers dictionary."""
return self.__detected_markers
def detected_markers_number(self) -> int:
"""Return detected markers number."""
return len(list(self.__detected_markers.keys()))
def draw_detected_markers(self, image: numpy.array, draw_marker: dict = None):
"""Draw detected markers.
Parameters:
image: image where to draw
draw_marker: ArucoMarker.draw parameters (if None, no marker drawn)
"""
if draw_marker is not None:
for marker_id, marker in self.__detected_markers.items():
marker.draw(image, self.__optic_parameters.K, self.__optic_parameters.D, **draw_marker)
def detect_board(self, image: numpy.array, board, expected_markers_number):
"""Detect ArUco markers board in image setting up the number of detected markers needed to agree detection.
!!! danger "DON'T MIRROR IMAGE"
It makes the markers detection to fail.
"""
# detect markers from gray picture
gray = cv.cvtColor(image, cv.COLOR_BGR2GRAY)
detected_markers_corners, detected_markers_ids, _ = aruco.detectMarkers(gray, self.__dictionary.markers, parameters = self.__parameters.internal)
# if all board markers are detected
if len(detected_markers_corners) == expected_markers_number:
self.__board = board
self.__board_corners_number, self.__board_corners, self.__board_corners_ids = aruco.interpolateCornersCharuco(detected_markers_corners, detected_markers_ids, gray, self.__board.model)
else:
self.__board = None
self.__board_corners_number = 0
self.__board_corners = []
self.__board_corners_ids = []
def draw_board(self, image: numpy.array):
"""Draw detected board corners in image."""
if self.__board != None:
cv.drawChessboardCorners(image, ((self.__board.size[0] - 1 ), (self.__board.size[1] - 1)), self.__board_corners, True)
def board_corners_number(self) -> int:
"""Get detected board corners number."""
return self.__board_corners_number
def board_corners_identifier(self) -> list[int]:
"""Get detected board corners identifier."""
return self.__board_corners_ids
def board_corners(self) -> list:
"""Get detected board corners."""
return self.__board_corners
class Observer():
"""Define ArUcoDetector observer to count how many times detection succeeded and how many times markers are detected."""
def __init__(self):
"""Initialize marker detection metrics."""
self.__try_count = 0
self.__success_count = 0
self.__detected_ids = []
@property
def metrics(self) -> tuple[int, dict]:
"""Get marker detection metrics.
Returns:
number of detect function call
dict with number of detection for each marker identifier
"""
return self.__try_count, self.__success_count, Counter(self.__detected_ids)
def reset(self):
"""Reset marker detection metrics."""
self.__try_count = 0
self.__success_count = 0
self.__detected_ids = []
def on_detect_markers(self, timestamp, aruco_detector, exception):
"""Update ArUco markers detection metrics."""
self.__try_count += 1
detected_markers_list = list(aruco_detector.detected_markers().keys())
if len(detected_markers_list):
self.__success_count += 1
self.__detected_ids.extend(detected_markers_list)
|