main.py 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143
  1. import asyncio
  2. import logging
  3. from robot_control.src.robot.controller import RobotController
  4. from robot_control.src.utils.config import ConfigParser, DefeederMagazineConfig
  5. from robot_control.src.vision.datamatrix import DataMatrixReader
  6. from robot_control.src.api.i2c_handler import I2C, MockI2C
  7. from robot_control.src.vendor.mcp3428 import MCP3428
  8. from robot_control.src.robot.pump_controller import PumpController
  9. from robot_control.src.api.gpio import PiGPIO, MockGPIO
  10. from robot_control.src.utils.logging import setup_logging
  11. from robot_control.src.robot.mag_distributor import MagDistributor
  12. class LoaderSystem:
  13. def __init__(self):
  14. # Load configuration
  15. self.config = ConfigParser().config
  16. setup_logging(self.config)
  17. gpio_config = self.config.gpio
  18. # Initialize GPIO (mock or real based on debug flag)
  19. if gpio_config.debug:
  20. self.gpio = MockGPIO()
  21. else:
  22. self.gpio = PiGPIO(out_pins=[gpio_config.pump_pin, gpio_config.valve_pin])
  23. self.logger = logging.getLogger(__name__)
  24. # Initialize camera system
  25. self.vision = DataMatrixReader(self.config.vision)
  26. self.logger.info("Initializing LoaderSystem")
  27. # Initialize I2C (mock or real based on debug flag)
  28. i2c_device_class = MCP3428 if not self.config.i2c.debug else MockI2C
  29. self.i2c = I2C(i2c_device_class)
  30. self.i2c.initialize()
  31. self.logger.info(f"I2C initialized with {i2c_device_class.__name__}")
  32. # Initialize pump controller
  33. self.pump_controller = PumpController(self.config, self.gpio)
  34. # Initialize magazine distributor
  35. self.mag_distributor = MagDistributor(self.config, self.gpio)
  36. # Create feeder and defeeder queues used for async handling of cell
  37. # Magazine -> MagDist -> Feeder -> Robot
  38. # Magazine <- MagDist <- Defeeder <- Robot
  39. self.feeder_queue: asyncio.Queue[int] = asyncio.Queue(self.config.feeder.max_num_cells)
  40. self.defeeder_queue: asyncio.Queue[DefeederMagazineConfig] = asyncio.Queue(self.config.defeeder.max_num_cells)
  41. # Pass all hardware interfaces to the controller
  42. self.controller = RobotController(
  43. self.config,
  44. self.gpio,
  45. self.i2c,
  46. self.vision,
  47. self.pump_controller,
  48. self.feeder_queue,
  49. self.defeeder_queue
  50. )
  51. async def run(self):
  52. """
  53. Main entry point for running the loader system.
  54. Starts all main async loops and ensures cleanup on exit.
  55. """
  56. await self.controller.connect()
  57. try:
  58. await asyncio.gather(
  59. self._loader_loop(), # Main loader orchestration loop
  60. self._poll_i2c_channels(), # Poll I2C sensors
  61. self._queue_monitor_loop(), # Monitor feeder/defeeder queues
  62. )
  63. finally:
  64. self.cleanup()
  65. self.logger.info("Cleaning up resources...")
  66. async def _poll_i2c_channels(self):
  67. """
  68. Periodically poll I2C channels for sensor readings.
  69. Handles pressure and end-effector state updates.
  70. """
  71. while True:
  72. try:
  73. readings = await self.i2c.read_channels([3, 4]) # channel 1 is handled on demand in Controller
  74. for channel, value in readings.items():
  75. self.logger.debug(f"Channel {channel} reading: {value}")
  76. if channel == 3: # Pressure reading
  77. self.pump_controller.handle_tank_reading(value)
  78. if channel == 4: # End-effector state
  79. state = self.pump_controller.check_endeffector_state(value)
  80. self.controller.set_suction_state(state)
  81. except Exception as e:
  82. self.logger.error(f"Error polling I2C channels: {str(e)}")
  83. await asyncio.sleep(1) # Poll every second
  84. async def _loader_loop(self):
  85. """
  86. Main loop for the loader system.
  87. Orchestrates cell preparation, slot filling, and measurement processing.
  88. """
  89. while True:
  90. await asyncio.sleep(0.1) # Avoid busy loop
  91. while True:
  92. # Prepare a cell in the feeder (returns True if a cell is ready)
  93. if not await self.controller.prepare_feeder_cell():
  94. break
  95. # Fill the next free slot (returns True if a cell was placed)
  96. if not await self.controller.fill_next_free_slot():
  97. break
  98. # Check for completed measurements and sort cells
  99. await self.controller.process_finished_measurements()
  100. async def _queue_monitor_loop(self):
  101. """
  102. Periodically checks feeder and defeeder queues and calls placeholder functions.
  103. Handles refilling the feeder and processing the defeeder.
  104. """
  105. while True:
  106. # Feeder: If queue below max, trigger refill placeholder
  107. if not self.feeder_queue.full():
  108. self.logger.info(f"Refilling feeder...")
  109. await asyncio.get_event_loop().run_in_executor(
  110. None, self.mag_distributor.mag_to_feeder
  111. )
  112. await self.feeder_queue.put(1) # Add to queue
  113. # Defeeder: If queue not empty, process next cell
  114. if not self.defeeder_queue.empty():
  115. magazine = await self.defeeder_queue.get() # Remove from queue
  116. self.logger.info(f"Processing defeeder to magazine {magazine.name}...")
  117. await asyncio.get_event_loop().run_in_executor(
  118. None, self.mag_distributor.defeeder_to_mag, magazine
  119. )
  120. await asyncio.sleep(2) # Adjust interval as needed
  121. def cleanup(self):
  122. """
  123. Cleanup hardware resources (GPIO, etc.).
  124. """
  125. self.gpio.cleanup() # Ensure PumpController cleans up gpio
  126. if __name__ == "__main__":
  127. loader_system = LoaderSystem()
  128. asyncio.run(loader_system.run())