Browse Source

refactor logging configuration; update max file size and backup count; improve logging messages and add throttling filter

Silas Gruen 10 months ago
parent
commit
a85a33c826

+ 2 - 2
robot-control/config/config.yaml

@@ -57,6 +57,6 @@ system_settings:
 logging:
   level: INFO
   file_path: logs/robot.log
-  max_file_size_mb: 10
-  backup_count: 5
+  max_file_size_mb: 1
+  backup_count: 3
   console_output: true

+ 2 - 2
robot-control/src/main.py

@@ -38,11 +38,11 @@ class LoaderSystem:
                     await self.controller.insert_cell_to_slot(cell, slot)
                 except Exception as e:
                     self.logger.error(f"Failed to process cell {cell_id}: {str(e)}")
-                    # TODO [SG]: do a break here?
+                    break
             
             # Check for completed measurements
             if not self.controller.work_queue:
-                self.logger.debug("No finished measurements in queue")
+                self.logger.warning("No finished measurements in queue")
                 continue
 
             completed_slot = self.controller.work_queue.pop(0)

+ 60 - 42
robot-control/src/robot/controller.py

@@ -73,43 +73,49 @@ class RobotController:
         # await self.movement.cleanup() TODO[SG]: Implement cleanup method in movement.py
         self.mqtt_handler.cleanup()
 
+    def get_device_by_id(self, device_id: str):
+        for device in self.devices:
+            if device.id == device_id:
+                return device
+        return None
+
+    def get_next_free_slot(self):
+        for device in self.devices:
+            for slot in device.slots:
+                if not slot.occupied:
+                    logger.info(f"Next free slot is {slot}")
+                    return slot
+                
+        logger.warning("No free slots available")
+        return None
+
     async def pick_cell_from_feeder(self):
         if self.gripper_occupied:
             logger.error("Gripper already occupied")
             return False
             
-        logger.info("Move to save position and pick cell from feeder...")
-        feeder_pos = self.feeder.approach_position
-        x, y, z = feeder_pos
-        # Move to safe height first
-        await self.movement.move_to_position(x, y, self.system_settings.safe_height)
-        # Move to pickup position
-        await self.movement.move_to_position(x, y, z)
+        feeder_pos = self.feeder.position
+        safe_pos = self.feeder.approach_position
+        logger.info(f"Moving to feeder position (safe) {safe_pos}...")
+        await self.movement.move_to_position(*safe_pos)
+        logger.info(f"Moving to feeder position {feeder_pos}...")
+        await self.movement.move_to_position(*feeder_pos)
+
         # Grip cell
         try:
             await self.movement.activate_endeffector()
             self.gripper_occupied = True
-
-            # Move back to safe height
-            await self.movement.move_to_position(x, y, self.system_settings.safe_height)
+            logger.info(f"Moving to feeder position (safe) {safe_pos}...")
+            await self.movement.move_to_position(*safe_pos)
             logger.info("Cell picked from feeder")
             return True
+        
         except Exception as e:
             logger.error(f"Failed to pick cell from feeder: {str(e)}")
             await self.movement.deactivate_endeffector() # TODO [SG]: Should deactivate here?
             self.gripper_occupied = False
             raise e
 
-    def get_next_free_slot(self):
-        for device in self.devices:
-            for slot in device.slots:
-                if not slot.occupied:
-                    logger.info(f"Next free slot is {slot}")
-                    return slot
-                
-        logger.error("No free slots available")
-        return None
-
     async def insert_cell_to_next_available(self, cell: Cell):
         if not self.gripper_occupied:
             logger.error("Gripper not occupied")
@@ -127,14 +133,18 @@ class RobotController:
             raise RuntimeError("Gripper not occupied")
 
         # Move to slot position
-        x, y, z = slot.position
-        # Move to safe height first
-        await self.movement.move_to_position(x, y, self.system_settings.safe_height)
-        # Move down to insertion position
-        await self.movement.move_to_position(x, y, z)
+        slot_device = self.get_device_by_id(slot.device_id)
+        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)
+        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}...")
+        await self.movement.move_to_position(*pos)
+
         # Release cell
-        if not await self.movement.deactivate_endeffector():
-            raise RuntimeError(f"Failed to release cell {cell.id}")     
+        await self.movement.deactivate_endeffector() 
             
         slot.occupied = True
         slot.cell_id = cell.id
@@ -151,7 +161,8 @@ class RobotController:
         )
         
         # Move back to safe height
-        await self.movement.move_to_position(x, y, self.system_settings.safe_height)
+        logger.info(f"Moving to slot position (safe) {safe_pos}...")
+        await self.movement.move_to_position(*safe_pos)
         logger.info(f"Cell {cell.id} inserted to {slot}")
         return True
 
@@ -160,22 +171,27 @@ class RobotController:
             logger.error("Gripper already occupied")
             return None
         
-        x, y, z = slot.position
-        # Move to safe height first
-        await self.movement.move_to_position(x, y, self.system_settings.safe_height)
-        # Move down to collection position
-        await self.movement.move_to_position(x, y, z)
+        slot_device = self.get_device_by_id(slot.device_id)
+        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)
+        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}...")
+        await self.movement.move_to_position(*pos)
+
         # Grip cell
         try:
-            if not await self.movement.activate_endeffector():
-                raise RuntimeError("Failed to grip cell")
+            await self.movement.activate_endeffector()
             self.gripper_occupied = True
             cell_id = slot.cell_id
             slot.occupied = False
             slot.cell_id = None
             
             # Move back to safe height
-            await self.movement.move_to_position(x, y, self.system_settings.safe_height)
+            logger.info(f"Moving to slot position (safe) {safe_pos}...")
+            await self.movement.move_to_position(*safe_pos)
             logger.info(f"Cell {cell_id} collected from {slot}")
             return cell_id
         except Exception as e:
@@ -205,16 +221,18 @@ class RobotController:
             logger.error("Cannot drop off: gripper not occupied")
             return
             
-        x, y, z = dropoff_grade.position
-        # Move to safe height first
-        await self.movement.move_to_position(x, y, self.system_settings.safe_height)
-        # Move to dropoff position
-        await self.movement.move_to_position(x, y, z)
+        pos = dropoff_grade.position
+        safe_pos = (pos[0], pos[1], self.system_settings.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}...")
+        await self.movement.move_to_position(*pos)
         # Release cell
         if not await self.movement.deactivate_endeffector():
             raise RuntimeError("Failed to release cell")
         self.gripper_occupied = False
 
         # Move back to safe height
-        await self.movement.move_to_position(x, y, self.system_settings.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}")

+ 1 - 9
robot-control/src/robot/movement.py

@@ -101,12 +101,4 @@ class RobotMovement:
         self.is_moving = False
         self.endeffector_active = False
         logger.warning("Emergency stop triggered!")
-        await self.grbl.send_gcode(['!', 'M5'])  # Feed hold + stop pump
-
-    async def wait_until_idle(self, timeout: Optional[float] = None) -> bool:
-        start_time = time.time()
-        while self.is_moving:
-            if timeout and (time.time() - start_time) > timeout:
-                return False
-            await asyncio.sleep(0.1)  # Non-blocking wait
-        return True
+        await self.grbl.send_gcode(['!', 'M5'])  # Feed hold + stop pump

+ 1 - 1
robot-control/src/utils/config.py

@@ -12,7 +12,7 @@ class SlotConfig:
     cell_id: str = None
 
     def __str__(self) -> str:
-        return f"Slot {self.slot_id}, Device: {self.device_id}, Pos: {self.position}"
+        return f"Slot {self.slot_id}, Device: {self.device_id}"
 
 @dataclass
 class DeviceConfig:

+ 31 - 1
robot-control/src/utils/logging.py

@@ -3,6 +3,7 @@ from logging.handlers import RotatingFileHandler
 import os
 from typing import Optional
 from utils.config import ConfigParser
+import time
 
 class LoggerSingleton:
     _instance: Optional[logging.Logger] = None
@@ -29,13 +30,42 @@ class LoggerSingleton:
             backupCount=log_config['backup_count']
         )
         file_formatter = logging.Formatter('%(asctime)s - %(name)s - %(levelname)s - %(message)s')
+        file_handler.addFilter(ThrottlingFilter(throttle_interval=1.0))
         file_handler.setFormatter(file_formatter)
         logger.addHandler(file_handler)
 
         if log_config['console_output']:
             console_handler = logging.StreamHandler()
+            console_handler.addFilter(ThrottlingFilter(throttle_interval=1.0))
             console_formatter = logging.Formatter('%(levelname)s: %(message)s')
             console_handler.setFormatter(console_formatter)
             logger.addHandler(console_handler)
 
-        return logger
+        return logger
+    
+    import logging
+import time
+
+class ThrottlingFilter(logging.Filter):
+    def __init__(self, name='', throttle_interval=10.0):
+        """
+        :param name: Filter name (can be left empty)
+        :param throttle_interval: Time interval (in seconds) that must pass before a duplicate message is logged.
+        """
+        super().__init__(name)
+        self.throttle_interval = throttle_interval
+        # A dictionary to store the last logged time for each unique message
+        self.last_logged = {}
+
+    def filter(self, record):
+        current_time = time.time()
+        # Use the log message as a key. For more complex scenarios, you could combine
+        # other record attributes like record.levelno, record.name, etc.
+        message_key = record.getMessage()
+        last_time = self.last_logged.get(message_key, 0)
+        
+        if current_time - last_time >= self.throttle_interval:
+            self.last_logged[message_key] = current_time
+            return True  # Allow the record to be logged
+        else:
+            return False  # Skip logging this record