main.py 5.9 KB

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