Parcourir la source

ref: update configuration handling with pydantic; replace LoggerSingleton with standard logging module;

Silas Gruen il y a 8 mois
Parent
commit
c6af701f62

+ 6 - 9
main.py

@@ -1,5 +1,5 @@
 import asyncio
-from robot_control.src.utils.logging import LoggerSingleton
+import logging
 from robot_control.src.robot.controller import RobotController
 from robot_control.src.utils.config import ConfigParser
 from robot_control.src.vision.datamatrix import DataMatrixReader
@@ -10,22 +10,19 @@ from robot_control.src.api.gpio import PiGPIO
 
 class LoaderSystem:
     def __init__(self):
-        pump_pin = self.config.get_gpio_config().get("pump_pin")
-        valve_pin = self.config.get_gpio_config().get("valve_pin")
-        self.gpio = PiGPIO([pump_pin, valve_pin], [])
+        self.config = ConfigParser().config
+        gpio_config = self.config.gpio
+        self.gpio = PiGPIO([gpio_config.pump_pin, gpio_config.valve_pin], [])
 
-        self.config = ConfigParser()
-        self.logger = LoggerSingleton.get_logger(self.config)
+        self.logger = logging.getLogger(__name__)
         self.controller = RobotController(self.config, self.gpio)
-        cam = self.config.get_vision_config().get("camera_id")
-        self.vision = DataMatrixReader(cam)
+        self.vision = DataMatrixReader(self.config.vision.camera_id)
         self.logger.info("Initializing LoaderSystem")
         self.vision.initialize()
         self.i2c = I2C(MCP3428)
         self.i2c.initialize()
         self.logger.info("I2C initialized for MCP3428")
 
-
         self.pump_controller = PumpController(self.config, self.gpio, self.logger)
 
     async def run(self):

+ 13 - 0
pyproject.toml

@@ -0,0 +1,13 @@
+[tool.poetry]
+name = "cell_loader_ctr"
+version = "0.1.0"
+description = "Cell Loader Control System"
+
+[tool.poetry.dependencies]
+python = "^3.8"
+pydantic = "^2.0.0"
+PyYAML = "^6.0"
+
+[build-system]
+requires = ["poetry-core>=1.0.0"]
+build-backend = "poetry.core.masonry.api"

+ 6 - 6
robot_control/config/config.yaml

@@ -1,5 +1,5 @@
 measurement_devices:
-  - id: "device_1"
+  - id: device_1
     position: [50.0, 50.0, 0.0]
     slots:
       - position: [10.0, 20.0, 0.0]
@@ -12,7 +12,7 @@ measurement_devices:
         occupied: False
         slot_id: 2
 
-  - id: "device_2"
+  - id: device_2
     position: [100.0, 50.0, 0.0]
     slots:
       - position: [10.0, 20.0, 0.0]
@@ -30,10 +30,10 @@ feeder:
   approach_position: [0.0, 0.0, 20.0]
 
 dropoff_grades:
-  accepted:
+  - id: accepted
     position: [0.0, 10.0, 0.0]
     capacity_threshold: 0.8
-  rejected:
+  - id: rejected
     position: [0.0, 20.0, 0.0]
     capacity_threshold: 0
 
@@ -60,7 +60,7 @@ vacuum:
   min_pressure_bar: 0.5
   max_pressure_bar: 1.0
   max_pump_time_s: 30
-  gripping_threshold_v: 0.8
+  gripping_threshold_bar: 0.8
   pump_watchdog_timeout_s: 30
 
 gpio:
@@ -68,7 +68,7 @@ gpio:
   pump_pin: 17
   valve_pin: 27
 
-system_settings:
+movement:
   speed: 400.0
   acceleration: 20.0
   safe_height: 25.0

+ 2 - 1
robot_control/requirements.txt

@@ -11,4 +11,5 @@ pytest-cov==6.0.0
 httpx==0.25.0
 paho-mqtt<2
 pyserial-asyncio>=0.6
-pigpio
+pigpio
+smbus2

+ 2 - 2
robot_control/src/api/grbl_handler.py

@@ -1,7 +1,7 @@
 import asyncio
 import serial_asyncio
 from typing import List
-from robot_control.src.utils.logging import LoggerSingleton
+import logging
 import datetime
 import collections
 
@@ -9,7 +9,7 @@ MOVE_RATE = 50
 APPROACHE_RATE = 10 
 CELL_CIRCLE_RADIUS = 0.35
 
-logger = LoggerSingleton.get_logger()
+logger = logging.getLogger(__name__)
 
 class GRBLHandler:
     def __init__(self, port: str, baudrate: int):

+ 2 - 2
robot_control/src/api/mqtt_handler.py

@@ -2,9 +2,9 @@ import paho.mqtt.client as mqtt
 from typing import Callable
 from pydantic import BaseModel
 import json
-from robot_control.src.utils.logging import LoggerSingleton
+import logging
 
-logger = LoggerSingleton.get_logger()
+logger = logging.getLogger(__name__)
 
 class MQTTDevice:
     def __init__(self, device_id: str, num_slots: int):

+ 27 - 34
robot_control/src/robot/controller.py

@@ -1,14 +1,14 @@
 from dataclasses import dataclass
 from enum import Enum
 from typing import List, Tuple
-from robot_control.src.utils.config import ConfigParser, SlotConfig, DeviceConfig
+from robot_control.src.utils.config import RobotConfig, SlotConfig, DeviceConfig, DropoffGradeConfig
 from robot_control.src.robot.movement import RobotMovement
-from robot_control.src.utils.logging import LoggerSingleton
+import logging
 from robot_control.src.api.mqtt_handler import MQTTHandler, MeasurementResult
 from robot_control.src.api.grbl_handler import GRBLHandler
 from robot_control.src.api.gpio import GPIOInterface
 
-logger = LoggerSingleton.get_logger()
+logger = logging.getLogger(__name__)
 
 class CellStatus(Enum):
     WAITING = "WAITING"
@@ -22,28 +22,23 @@ class Cell:
     status: CellStatus = CellStatus.WAITING
     capacity: float = None
 
-class DropoffGrade:
-    def __init__(self, name: str, x: float, y: float, z: float):
-        self.name = name
-        self.position = (x, y, z)
-
 class RobotController:
-    def __init__(self, config: ConfigParser, gpio_handler: GPIOInterface):
+    def __init__(self, config: RobotConfig, gpio_handler: GPIOInterface):
         self.config = config
-        self.cells:dict[Cell] = {}
-        self.devices = self.config.get_devices()
-        self.feeder = self.config.get_feeder()
-        self.dropoff_grades = self.config.get_dropoff_grades()
-        self.rejected_grade = self.dropoff_grades['rejected']
-        self.system_settings = self.config.get_system_settings()
+        self.cells: dict[Cell] = {}
+        self.devices = self.config.measurement_devices
+        self.feeder = self.config.feeder
+        self.dropoff_grades = self.config.dropoff_grades
         
         # Initialize robot movement
-        grbl_config = self.config.get_grbl_config()
-        self.grbl_handler = GRBLHandler(grbl_config.get('port'), grbl_config.get('baudrate'))
+        self.grbl_handler = GRBLHandler(
+            self.config.grbl.port, 
+            self.config.grbl.baudrate
+        )
         self.movement = RobotMovement(self.config, self.grbl_handler)
 
         self.gpio = gpio_handler
-        self.valve_pin = config.get_gpio_config().get("valve_pin")
+        self.valve_pin = self.config.gpio.valve_pin
         
         # Initialize with configured values
         self.total_slots = sum(len(device.slots) for device in self.devices)
@@ -53,12 +48,12 @@ class RobotController:
         self.suction_state = False
         
         # Initialize MQTT handler
-        mqtt_config = self.config.get_mqtt_config()
+        mqtt = self.config.mqtt
         self.mqtt_handler = MQTTHandler(
-            broker=mqtt_config.get('broker'),
-            port=mqtt_config.get('port'),
-            username=mqtt_config.get('username'),
-            password=mqtt_config.get('password'),
+            broker=mqtt.broker,
+            port=mqtt.port,
+            username=mqtt.username,
+            password=mqtt.password,
         )
         
         # Register all devices with MQTT handler
@@ -94,7 +89,7 @@ class RobotController:
 
     async def connect(self):
         await self.grbl_handler.connect()
-        await self.movement.set_speed(self.system_settings.speed)
+        await self.movement.set_speed(self.config.movement.speed)
 
     async def cleanup(self):
         """Cleanup resources on shutdown"""
@@ -214,7 +209,7 @@ class RobotController:
         if not slot_device:
             raise RuntimeError(f"Device {slot.device_id} not found")
         pos = [sum(el) for el in zip(slot.position, slot_device.position)]
-        safe_pos = (pos[0], pos[1], self.system_settings.safe_height)
+        safe_pos = (pos[0], pos[1], self.config.movement.safe_height)
         logger.info(f"Moving to slot position (safe) {safe_pos}...")
         await self.movement.move_to_position(*safe_pos)
         logger.info(f"Moving to slot position {pos}...")
@@ -250,7 +245,7 @@ class RobotController:
         if not slot_device:
             raise RuntimeError(f"Device {slot.device_id} not found")
         pos = [sum(el) for el in zip(slot.position, slot_device.position)]
-        safe_pos = (pos[0], pos[1], self.system_settings.safe_height)
+        safe_pos = (pos[0], pos[1], self.config.movement.safe_height)
         logger.info(f"Moving to slot position (safe) {safe_pos}...")
         await self.movement.move_to_position(*safe_pos)
         logger.info(f"Moving to slot position {pos}...")
@@ -286,24 +281,22 @@ class RobotController:
             del self.cells[cell.id] # Remove cell from our database TODO [SG]: Should we keep it for history?
 
         if cell.status is CellStatus.ERROR:
-            await self.dropoff_cell(self.rejected_grade)
-            logger.info(f"Cell {cell.id} sorted to rejected grade")
-            return True
-        for name, grade in self.dropoff_grades.items():
+            cell.capacity = 0 # will be dropped off in the lowest grade
+        for grade in self.dropoff_grades:
             if cell.capacity >= grade.capacity_threshold:
                 await self.dropoff_cell(grade)
-                logger.info(f"Cell {cell.id} sorted to grade {name}")
+                logger.info(f"Cell {cell.id} sorted to grade {grade.id}")
                 return True
         logger.error(f"No suitable grade found for cell {cell.id} with capacity {cell.capacity}")
         return False
 
-    async def dropoff_cell(self, dropoff_grade: DropoffGrade):
+    async def dropoff_cell(self, dropoff_grade: DropoffGradeConfig):
         if not self.gripper_occupied:
             logger.error("Cannot drop off: gripper not occupied")
             return
             
         pos = dropoff_grade.position
-        safe_pos = (pos[0], pos[1], self.system_settings.safe_height)
+        safe_pos = (pos[0], pos[1], self.config.movement.safe_height)
         logger.info(f"Moving to dropoff (safe) {safe_pos}...")
         await self.movement.move_to_position(*safe_pos)
         logger.info(f"Moving to dropoff position {pos}...")
@@ -316,4 +309,4 @@ class RobotController:
         # Move back to safe height
         logger.info(f"Moving to dropoff position (safe) {safe_pos}...")
         await self.movement.move_to_position(*safe_pos)
-        logger.info(f"Cell dropped off at grade {dropoff_grade.name}")
+        logger.info(f"Cell dropped off at grade {dropoff_grade.id}")

+ 6 - 7
robot_control/src/robot/movement.py

@@ -3,27 +3,26 @@ import time
 import asyncio
 import pigpio
 from robot_control.src.api.grbl_handler import GRBLHandler
-from robot_control.src.utils.logging import LoggerSingleton
-from robot_control.src.utils.config import ConfigParser
+import logging
+from robot_control.src.utils.config import RobotConfig
 
 
-logger = LoggerSingleton.get_logger()
+logger = logging.getLogger(__name__)
 
 class RobotMovement:
     """Class for controlling robot movements and end effector operations."""
 
-    def __init__(self, config: ConfigParser, grbl: GRBLHandler):
+    def __init__(self, config: RobotConfig, grbl: GRBLHandler):
         """Initialize the robot movement controller.
 
         Args:
             grbl (GRBLHandler): GRBL communication handler
-            config (ConfigParser): Configuration parser instance
+            config (RobotConfig): Configuration instance
         """
         self.config = config        
 
         # Setting configs
-        sys_config = config.get_system_settings()
-        self.speed: float = sys_config.speed
+        self.speed: float = self.config.movement.speed
 
         # Basic variables for robot movement
         self.home_position: tuple[float, float, float] = (0.0, 0.0, 0.0)

+ 9 - 10
robot_control/src/robot/pump_controller.py

@@ -1,19 +1,18 @@
 import time
 import pigpio
-from robot_control.src.utils.config import ConfigParser
+from robot_control.src.utils.config import RobotConfig
 from robot_control.src.api.gpio import GPIOInterface
 
 class PumpController:
-    def __init__(self, config:ConfigParser, gpio:GPIOInterface, logger):
+    def __init__(self, config:RobotConfig, gpio:GPIOInterface, logger):
         self.logger = logger
-        vacuum_config = config.get_vacuum_config()
-        self.pressure_threshold_on = vacuum_config.get("min_pressure_bar")
-        self.pressure_threshold_off = vacuum_config.get("max_pressure_bar")
-        self.pump_watchdog_timeout = vacuum_config.get("pump_watchdog_timeout", 30)  # Default to 30 seconds
-        self.gripping_threshold = vacuum_config.get("gripping_threshold_v")
-
-        gpio_config = config.get_gpio_config()
-        self.pump_pin = gpio_config.get("pump_pin")
+        self.pressure_threshold_on = config.vacuum.min_pressure_bar
+        self.pressure_threshold_off = config.vacuum.max_pressure_bar 
+        self.pump_watchdog_timeout = config.vacuum.pump_watchdog_timeout_s
+        self.gripping_threshold = config.vacuum.gripping_threshold_bar
+
+        gpio_config = config.gpio
+        self.pump_pin = gpio_config.pump_pin
         self.pump_last_activated = None
         self.pump_active = False
         self.gpio = gpio

+ 120 - 128
robot_control/src/utils/config.py

@@ -1,151 +1,143 @@
-from dataclasses import dataclass
-from typing import List, Dict, Tuple
-import yaml
 from pathlib import Path
+from typing import List, Dict, Tuple, Optional
+from pydantic import BaseModel, Field, model_validator, field_validator
+import yaml
 
-@dataclass
-class SlotConfig:
+class SlotConfig(BaseModel):
     position: Tuple[float, float, float]
-    occupied: bool
+    occupied: bool = False
     slot_id: int
-    device_id: str
-    cell_id: str = None
+    device_id: Optional[str] = None
+    cell_id: Optional[str] = None
 
     def __str__(self) -> str:
         return f"Slot {self.slot_id}, Device: {self.device_id}"
 
-@dataclass
-class DeviceConfig:
+class DeviceConfig(BaseModel):
     id: str
     position: Tuple[float, float, float]
     slots: List[SlotConfig]
 
-@dataclass
-class FeederConfig:
+    @field_validator('slots')
+    @classmethod
+    def validate_slots(cls, v):
+        slot_ids = [slot.slot_id for slot in v]
+        if len(slot_ids) != len(set(slot_ids)):
+            raise ValueError("Duplicate slot IDs found")
+        return v
+
+class FeederConfig(BaseModel):
     position: Tuple[float, float, float]
     approach_position: Tuple[float, float, float]
 
-@dataclass
-class DropoffGradeConfig:
-    name: str
+class DropoffGradeConfig(BaseModel):
+    id: str
     position: Tuple[float, float, float]
-    capacity_threshold: float
+    capacity_threshold: float = Field(ge=0.0, le=1.0)
+
+class MQTTConfig(BaseModel):
+    broker: str = "localhost"
+    port: int = Field(default=1883, ge=1, le=65535)
+    username: Optional[str] = None
+    password: Optional[str] = None
+    keepalive: int = Field(default=60, ge=0)
+
+class GRBLConfig(BaseModel):
+    port: str = "debug"
+    baudrate: int = Field(default=115200, ge=9600)
+
+class VisionConfig(BaseModel):
+    camera_id: int = 0
+    resolution: Tuple[int, int] = (640, 480)
+    frame_rate: int = Field(default=30, ge=1)
+    exposure: float = Field(default=0.1, ge=0.0)
+    gain: float = Field(default=1.0, ge=0.0)
+
+class VacuumConfig(BaseModel):
+    min_pressure_bar: float = Field(default=0.5, ge=-1.0, le=1.0)
+    max_pressure_bar: float = Field(default=1.0, ge=-1.0, le=1.0)
+    max_pump_time_s: float = Field(default=30.0, ge=0.0)
+    gripping_threshold_bar: float = Field(default=0.8, ge=-1.0, le=1.0)
+    pump_watchdog_timeout_s: float = Field(default=30.0, ge=0.0)
+
+    @model_validator(mode='after')
+    def validate_pressure(self) -> 'VacuumConfig':
+        if self.min_pressure_bar >= self.max_pressure_bar:
+            raise ValueError("min_pressure must be less than max_pressure")
+        return self
 
-@dataclass
-class SystemConfig:
-    speed: float
-    acceleration: float
-    safe_height: float
+class GPIOConfig(BaseModel):
+    debug: bool = False
+    pump_pin: int = Field(default=17, ge=0)
+    valve_pin: int = Field(default=27, ge=0)
+
+class MovementConfig(BaseModel):
+    speed: float = Field(default=400.0, ge=0.0)
+    acceleration: float = Field(default=20.0, ge=0.0)
+    safe_height: float = Field(default=25.0, ge=0.0)
+
+class LoggingConfig(BaseModel):
+    level: str = Field(default="INFO")
+    file_path: Path = Field(default=Path("logs/robot.log"))
+    max_file_size_mb: int = Field(default=1, ge=0)
+    backup_count: int = Field(default=3, ge=0)
+    console_output: bool = True
+
+    @field_validator('level')
+    @classmethod
+    def validate_log_level(cls, v):
+        valid_levels = ['DEBUG', 'INFO', 'WARNING', 'ERROR', 'CRITICAL']
+        if v.upper() not in valid_levels:
+            raise ValueError(f"Log level must be one of {valid_levels}")
+        return v.upper()
+
+class RobotConfig(BaseModel):
+    measurement_devices: List[DeviceConfig]
+    feeder: FeederConfig
+    dropoff_grades: List[DropoffGradeConfig]
+    mqtt: MQTTConfig
+    grbl: GRBLConfig
+    vision: VisionConfig
+    vacuum: VacuumConfig
+    gpio: GPIOConfig
+    movement: MovementConfig
+    logging: LoggingConfig
+
+    @model_validator(mode='after')
+    def validate_dropoff_grades(self) -> 'RobotConfig':
+        # Sort grades by threshold in descending order for consistent behavior
+        sorted_grades = sorted(self.dropoff_grades, key=lambda x: x.capacity_threshold, reverse=True)
+        for i in range(1, len(sorted_grades)):
+            if sorted_grades[i-1].capacity_threshold <= sorted_grades[i].capacity_threshold:
+                raise ValueError(
+                    f"Dropoff grade thresholds must be in strictly descending order. Found: "
+                    f"Grade {sorted_grades[i-1].id} ({sorted_grades[i-1].capacity_threshold}) <= "
+                    f"Grade {sorted_grades[i].id} ({sorted_grades[i].capacity_threshold})"
+                )
+        # Store sorted grades to ensure consistent behavior
+        self.dropoff_grades = sorted_grades
+        return self
 
 class ConfigParser:
     def __init__(self, config_path: str = "robot_control/config/config.yaml"):
         self.config_path = Path(config_path)
-        self.config = self._load_config()
+        self._config = self._load_config()
 
-    def _load_config(self):
+    def _load_config(self) -> RobotConfig:
+        if not self.config_path.exists():
+            raise FileNotFoundError(f"Config file not found: {self.config_path}")
+        
         with open(self.config_path, 'r') as f:
-            return yaml.safe_load(f)
-
-    def get_devices(self) -> List[DeviceConfig]:
-        devices = []
-        for device in self.config['measurement_devices']:
-            slots = [
-                SlotConfig(
-                    position=tuple(slot['position']),
-                    occupied=slot['occupied'],
-                    slot_id=slot['slot_id'],
-                    device_id=device['id'],
-                    cell_id=slot['cell_id'] if slot['occupied'] else None,
-                )
-                for slot in device['slots']
-            ]
-            devices.append(DeviceConfig(
-                id=device['id'],
-                position=tuple(device['position']),
-                slots=slots
-            ))
-        return devices
-
-    def get_feeder(self) -> FeederConfig:
-        feeder = self.config['feeder']
-        return FeederConfig(
-            position=tuple(feeder['position']),
-            approach_position=tuple(feeder['approach_position'])
-        )
-
-    def get_dropoff_grades(self) -> Dict[str, DropoffGradeConfig]:
-        grades = {}
-        for name, grade in self.config['dropoff_grades'].items():
-            grades[name] = DropoffGradeConfig(
-                name = name,
-                position=tuple(grade['position']),
-                capacity_threshold=grade['capacity_threshold']
-            )
-        return grades
-
-    def get_system_settings(self) -> SystemConfig:
-        settings = self.config['system_settings']
-        return SystemConfig(
-            speed=settings['speed'],
-            acceleration=settings['acceleration'],
-            safe_height=settings['safe_height']
-        )
-
-    def get_mqtt_config(self) -> dict:
-        """Get MQTT broker configuration"""
-        mqtt_config = self.config.get('mqtt', {})
-        return {
-            'broker': mqtt_config.get('broker', 'localhost'),
-            'port': mqtt_config.get('port', 1883),
-            'username': mqtt_config.get('username', None),
-            'password': mqtt_config.get('password', None),
-            'keepalive': mqtt_config.get('keepalive', 60)
-        }
-    
-    def get_grbl_config(self) -> dict:
-        """Get GRBL handler configuration"""
-        grbl_config = self.config.get('grbl', {})
-        return {
-            'port': grbl_config.get('port', None),
-            'baudrate': grbl_config.get('baudrate', 115200),
-        }
-    
-    def get_vision_config(self) -> dict:
-        """Get vision system configuration"""
-        vision_config = self.config.get('vision', {})
-        return {
-            'camera_id': vision_config.get('camera_id', 0),
-            'resolution': tuple(vision_config.get('resolution', (640, 480))),
-            'frame_rate': vision_config.get('frame_rate', 30),
-            'exposure': vision_config.get('exposure', 0.1),
-            'gain': vision_config.get('gain', 1.0)
-        }
-    
-    def get_vacuum_config(self) -> dict:
-        """Get vacuum system configuration"""
-        vacuum_config = self.config.get('vacuum', {})
-        return {
-            'min_pressure_bar': vacuum_config.get('min_pressure_bar', 0),
-            'max_pressure_bar': vacuum_config.get('max_pressure_bar', 0),
-            'max_pump_time_s': vacuum_config.get('max_pump_time_s', 30),
-            'gripping_threshold_v': vacuum_config.get('gripping_threshold_v', 0.8)
-        }
-    
-    def get_gpio_config(self) -> dict:
-        """Get gpio system configuration"""
-        gpio_config = self.config.get('gpio', {})
-        return {
-            'pump_pin': gpio_config.get('pump_pin', 17),
-            'valve_pin': gpio_config.get('valve_pin', 27)
-        }
-
-    def get_logging_config(self) -> dict:
-        """Get logging configuration"""
-        log_config = self.config.get('logging', {})
-        return {
-            'level': log_config.get('level', 'INFO'),
-            'file_path': log_config.get('file_path', 'logs/robot.log'),
-            'max_file_size_mb': log_config.get('max_file_size_mb', 10),
-            'backup_count': log_config.get('backup_count', 5),
-            'console_output': log_config.get('console_output', True)
-        }
+            config_dict = yaml.safe_load(f)
+
+            # Set device_id for each slot before creating the config
+            for device in config_dict['measurement_devices']:
+                device_id = device['id']
+                for slot in device['slots']:
+                    slot['device_id'] = device_id
+                    
+            return RobotConfig(**config_dict)
+
+    @property
+    def config(self) -> RobotConfig:
+        return self._config

+ 12 - 12
robot_control/src/utils/logging.py

@@ -2,7 +2,7 @@ import logging
 from logging.handlers import RotatingFileHandler
 import os
 from typing import Optional
-from .config import ConfigParser
+from .config import RobotConfig
 import time
 
 THROTTLING_FILTER_ENABLED = False
@@ -11,25 +11,25 @@ class LoggerSingleton:
     _instance: Optional[logging.Logger] = None
 
     @classmethod
-    def get_logger(cls, config: Optional[ConfigParser] = None) -> logging.Logger:
-        if config is None:
-            config = ConfigParser()
+    def get_logger(cls, config: Optional[RobotConfig] = None) -> logging.Logger:
+        # if config is None:
+        #     config = RobotConfig()
         if cls._instance is None and config is not None:
             cls._instance = cls._setup_logger(config)
         return cls._instance
 
     @staticmethod
-    def _setup_logger(config: ConfigParser) -> logging.Logger:
-        log_config = config.get_logging_config()
+    def _setup_logger(config: RobotConfig) -> logging.Logger:
+        log_config = config.logging
         logger = logging.getLogger('robot_control')
-        logger.setLevel(getattr(logging, log_config['level']))
+        logger.setLevel(getattr(logging, log_config.level))
 
-        os.makedirs(os.path.dirname(log_config['file_path']), exist_ok=True)
+        os.makedirs(os.path.dirname(log_config.file_path), exist_ok=True)
 
         file_handler = RotatingFileHandler(
-            log_config['file_path'],
-            maxBytes=log_config['max_file_size_mb'] * 1024 * 1024,
-            backupCount=log_config['backup_count']
+            log_config.file_path,
+            maxBytes=log_config.max_file_size_mb * 1024 * 1024,
+            backupCount=log_config.backup_count
         )
         file_formatter = logging.Formatter('%(asctime)s - %(name)s - %(levelname)s - %(message)s')
         if THROTTLING_FILTER_ENABLED:
@@ -37,7 +37,7 @@ class LoggerSingleton:
         file_handler.setFormatter(file_formatter)
         logger.addHandler(file_handler)
 
-        if log_config['console_output']:
+        if log_config.console_output:
             console_handler = logging.StreamHandler()
             if THROTTLING_FILTER_ENABLED:
                 console_handler.addFilter(ThrottlingFilter())

+ 3 - 2
robot_control/src/vision/datamatrix.py

@@ -1,9 +1,10 @@
 import cv2
 from pylibdmtx.pylibdmtx import decode
-from robot_control.src.utils.logging import LoggerSingleton
+import logging
 from pathlib import Path
 
-logger = LoggerSingleton.get_logger()
+logger = logging.getLogger(__name__)
+
 
 class TestCamera:
     def __init__(self, test_files_path: str):

+ 0 - 1
tests/test_api.py

@@ -1,5 +1,4 @@
 import pytest
-from fastapi.testclient import TestClient
 from robot_control.src.api.mqtt_handler import MQTTHandler, MeasurementResult, mqtt
 from unittest.mock import Mock, patch
 

+ 5 - 5
tests/test_robot.py

@@ -7,15 +7,15 @@ from robot_control.src.api.gpio import MockGPIO
 
 @pytest.fixture
 def robot_movement():
-    config = ConfigParser()
-    grbl_config = config.get_grbl_config()
-    grbl_handler = GRBLHandler(grbl_config.get('port'), grbl_config.get('baudrate'))
+    config = ConfigParser().config
+    grbl = config.grbl
+    grbl_handler = GRBLHandler(grbl.port, grbl.baudrate)
     return RobotMovement(config, grbl_handler)
 
 @pytest.fixture
 def robot_controller():
-    config = ConfigParser()
-    config.config["mqtt"]["broker"] = "debug" # connects to test mqtt broker
+    config = ConfigParser().config
+    config.mqtt.broker = "debug"  # connects to test mqtt broker
     mock_gpio = MockGPIO()
     controller = RobotController(config, gpio_handler=mock_gpio)
     return controller