@@ -24,7 +24,7 @@ class IYOEOHandler(ABC):
2424 """
2525
2626 @abstractmethod
27- def configure (self , config : parameters . Params ) -> None :
27+ def configure (self , yoeo_config ) -> None :
2828 """
2929 Allows to (re-) configure the YOEO handler.
3030 """
@@ -100,7 +100,7 @@ class YOEOHandlerTemplate(IYOEOHandler):
100100
101101 def __init__ (
102102 self ,
103- config : parameters . Params ,
103+ yoeo_config ,
104104 model_directory : str ,
105105 det_class_names : list [str ],
106106 det_robot_class_ids : list [int ],
@@ -119,12 +119,12 @@ def __init__(
119119 self ._seg_class_names : list [str ] = seg_class_names
120120 self ._seg_masks : dict = dict ()
121121
122- self ._use_caching : bool = config .caching
122+ self ._use_caching : bool = yoeo_config .caching
123123
124124 logger .debug ("Leaving YOEOHandlerTemplate constructor" )
125125
126- def configure (self , config : parameters . Params ) -> None :
127- self ._use_caching = config .caching
126+ def configure (self , yoeo_config ) -> None :
127+ self ._use_caching = yoeo_config .caching
128128
129129 def get_available_detection_class_names (self ) -> list [str ]:
130130 return self ._det_class_names
@@ -213,7 +213,7 @@ class YOEOHandlerONNX(YOEOHandlerTemplate):
213213
214214 def __init__ (
215215 self ,
216- config : parameters . Params ,
216+ yoeo_config ,
217217 model_directory : str ,
218218 det_class_names : list [str ],
219219 det_robot_class_ids : list [int ],
@@ -240,8 +240,8 @@ def __init__(
240240 self ._det_postprocessor : utils .IDetectionPostProcessor = utils .DefaultDetectionPostProcessor (
241241 image_preprocessor = self ._img_preprocessor ,
242242 output_img_size = self ._input_layer .shape [2 ],
243- conf_thresh = config . yoeo .conf_threshold ,
244- nms_thresh = config . yoeo .nms_threshold ,
243+ conf_thresh = yoeo_config .conf_threshold ,
244+ nms_thresh = yoeo_config .nms_threshold ,
245245 robot_class_ids = self .get_robot_class_ids (),
246246 )
247247 self ._seg_postprocessor : utils .ISegmentationPostProcessor = utils .DefaultSegmentationPostProcessor (
@@ -250,13 +250,13 @@ def __init__(
250250
251251 logger .debug (f"Leaving { self .__class__ .__name__ } constructor" )
252252
253- def configure (self , config : parameters . Params ) -> None :
253+ def configure (self , yoeo_config ) -> None :
254254 super ().configure (config )
255255 self ._det_postprocessor .configure (
256256 image_preprocessor = self ._img_preprocessor ,
257257 output_img_size = self ._input_layer .shape [2 ],
258- conf_thresh = config . yoeo .conf_threshold ,
259- nms_thresh = config . yoeo .nms_threshold ,
258+ conf_thresh = yoeo_config .conf_threshold ,
259+ nms_thresh = yoeo_config .nms_threshold ,
260260 robot_class_ids = self .get_robot_class_ids (),
261261 )
262262
@@ -286,7 +286,7 @@ class YOEOHandlerOpenVino(YOEOHandlerTemplate):
286286
287287 def __init__ (
288288 self ,
289- config : parameters . Params ,
289+ yoeo_config ,
290290 model_directory : str ,
291291 det_class_names : list [str ],
292292 det_robot_class_ids : list [int ],
@@ -322,8 +322,8 @@ def __init__(
322322 self ._det_postprocessor : utils .IDetectionPostProcessor = utils .DefaultDetectionPostProcessor (
323323 image_preprocessor = self ._img_preprocessor ,
324324 output_img_size = self ._input_layer .shape [2 ],
325- conf_thresh = config . yoeo .conf_threshold ,
326- nms_thresh = config . yoeo .nms_threshold ,
325+ conf_thresh = yoeo_config .conf_threshold ,
326+ nms_thresh = yoeo_config .nms_threshold ,
327327 robot_class_ids = self .get_robot_class_ids (),
328328 )
329329 self ._seg_postprocessor : utils .ISegmentationPostProcessor = utils .DefaultSegmentationPostProcessor (
@@ -339,13 +339,13 @@ def _select_device(self) -> str:
339339 device = "CPU"
340340 return device
341341
342- def configure (self , config : parameters . Params ) -> None :
342+ def configure (self , yoeo_config ) -> None :
343343 super ().configure (config )
344344 self ._det_postprocessor .configure (
345345 image_preprocessor = self ._img_preprocessor ,
346346 output_img_size = self ._input_layer .shape [2 ],
347- conf_thresh = config . yoeo .conf_threshold ,
348- nms_thresh = config . yoeo .nms_threshold ,
347+ conf_thresh = yoeo_config .conf_threshold ,
348+ nms_thresh = yoeo_config .nms_threshold ,
349349 robot_class_ids = self .get_robot_class_ids (),
350350 )
351351
@@ -374,7 +374,7 @@ class YOEOHandlerPytorch(YOEOHandlerTemplate):
374374
375375 def __init__ (
376376 self ,
377- config : parameters . Params ,
377+ yoeo_config ,
378378 model_directory : str ,
379379 det_class_names : list [str ],
380380 det_robot_class_ids : list [int ],
@@ -400,8 +400,8 @@ def __init__(
400400 logger .debug (f"Loading files...\n \t { config_path } \n \t { weights_path } " )
401401 self ._model = torch_models .load_model (config_path , weights_path )
402402
403- self ._conf_thresh : float = config . yoeo .conf_threshold
404- self ._nms_thresh : float = config . yoeo .nms_threshold
403+ self ._conf_thresh : float = yoeo_config .conf_threshold
404+ self ._nms_thresh : float = yoeo_config .nms_threshold
405405 self ._group_config : torch_GroupConfig = self ._update_group_config ()
406406
407407 logger .debug (f"Leaving { self .__class__ .__name__ } constructor" )
@@ -411,10 +411,10 @@ def _update_group_config(self):
411411
412412 return self .torch_group_config (group_ids = robot_class_ids , surrogate_id = robot_class_ids [0 ])
413413
414- def configure (self , config : parameters . Params ) -> None :
414+ def configure (self , yoeo_config ) -> None :
415415 super ().configure (config )
416- self ._conf_thresh = config . yoeo .conf_threshold
417- self ._nms_thresh = config . yoeo .nms_threshold
416+ self ._conf_thresh = yoeo_config .conf_threshold
417+ self ._nms_thresh = yoeo_config .nms_threshold
418418 self ._group_config = self ._update_group_config ()
419419
420420 @staticmethod
@@ -448,7 +448,7 @@ class YOEOHandlerTVM(YOEOHandlerTemplate):
448448
449449 def __init__ (
450450 self ,
451- config : parameters . Params ,
451+ yoeo_config ,
452452 model_directory : str ,
453453 det_class_names : list [str ],
454454 det_robot_class_ids : list [int ],
@@ -487,8 +487,8 @@ def __init__(
487487 self ._det_postprocessor : utils .IDetectionPostProcessor = utils .DefaultDetectionPostProcessor (
488488 image_preprocessor = self ._img_preprocessor ,
489489 output_img_size = self ._input_layer_shape [2 ],
490- conf_thresh = config . yoeo .conf_threshold ,
491- nms_thresh = config . yoeo .nms_threshold ,
490+ conf_thresh = yoeo_config .conf_threshold ,
491+ nms_thresh = yoeo_config .nms_threshold ,
492492 robot_class_ids = self .get_robot_class_ids (),
493493 )
494494 self ._seg_postprocessor : utils .ISegmentationPostProcessor = utils .DefaultSegmentationPostProcessor (
@@ -497,13 +497,13 @@ def __init__(
497497
498498 logger .debug (f"Leaving { self .__class__ .__name__ } constructor" )
499499
500- def configure (self , config : parameters . Params ) -> None :
500+ def configure (self , yoeo_config ) -> None :
501501 super ().configure (config )
502502 self ._det_postprocessor .configure (
503503 image_preprocessor = self ._img_preprocessor ,
504504 output_img_size = self ._input_layer_shape [2 ],
505- conf_thresh = config . yoeo .conf_threshold ,
506- nms_thresh = config . yoeo .nms_threshold ,
505+ conf_thresh = yoeo_config .conf_threshold ,
506+ nms_thresh = yoeo_config .nms_threshold ,
507507 robot_class_ids = self .get_robot_class_ids (),
508508 )
509509
0 commit comments