integration_test.py 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  1. import signal
  2. import sys
  3. import asyncio
  4. import logging
  5. from robot_control.src.robot.controller import RobotController, Cell, CellStatus
  6. from robot_control.src.utils.config import ConfigParser
  7. from robot_control.src.utils.logging import setup_logging
  8. from robot_control.src.vision.datamatrix import DataMatrixReader
  9. from robot_control.src.api.i2c_handler import I2C, MockI2C
  10. from robot_control.src.vendor.mcp3428 import MCP3428
  11. from robot_control.src.robot.pump_controller import PumpController
  12. from robot_control.src.api.gpio import PiGPIO, MockGPIO
  13. """
  14. This is a test script for the loader system.
  15. It initializes the robot controller, vision system, and I2C handler,
  16. """
  17. async def wait_for_enter():
  18. # Use asyncio.Event to coordinate between input and async code
  19. event = asyncio.Event()
  20. def input_callback():
  21. logging.info("Press Enter to continue...")
  22. input() # Wait for Enter
  23. event.set()
  24. # Run input in a separate thread to not block the event loop
  25. loop = asyncio.get_running_loop()
  26. await loop.run_in_executor(None, input_callback)
  27. await event.wait()
  28. class LoaderSystem:
  29. def __init__(self):
  30. self.config = ConfigParser().config
  31. setup_logging(self.config) # Set up logging with config
  32. gpio_config = self.config.gpio
  33. if gpio_config.debug:
  34. self.gpio = MockGPIO()
  35. else:
  36. self.gpio = PiGPIO(out_pins=[gpio_config.pump_pin, gpio_config.valve_pin])
  37. # Initialize vision system
  38. self.vision = DataMatrixReader(self.config.vision)
  39. # Initialize pump controller
  40. self.pump_controller = PumpController(self.config, self.gpio)
  41. i2c_device_class = MCP3428 if not self.config.i2c.debug else MockI2C
  42. self.i2c = I2C(i2c_device_class)
  43. self.feeder_queue: asyncio.Queue[int] = asyncio.Queue(self.config.feeder.max_capacity)
  44. self.defeeder_queue: asyncio.Queue[int] = asyncio.Queue(self.config.defeeder.max_capacity)
  45. # Initialize robot controller with all required arguments
  46. self.controller = RobotController(
  47. self.config,
  48. self.gpio,
  49. self.i2c,
  50. self.vision,
  51. self.pump_controller,
  52. self.feeder_queue,
  53. self.defeeder_queue
  54. )
  55. self.logger = logging.getLogger(__name__)
  56. self.logger.info("Initializing LoaderSystem")
  57. self.vision.initialize()
  58. # Test stuff
  59. self.test_slot = self.config.measurement_devices[0].slots[3]
  60. # Use mock I2C device if debug is enabled
  61. self.i2c.initialize()
  62. self.logger.info(f"I2C initialized with {i2c_device_class.__name__}")
  63. self.pump_controller = PumpController(self.config, self.gpio)
  64. async def run(self):
  65. await self.controller.connect()
  66. await asyncio.gather(
  67. self._loader_loop(),
  68. self._poll_i2c_channels()
  69. )
  70. async def _poll_i2c_channels(self):
  71. while True:
  72. try:
  73. readings = await self.i2c.read_channels([1, 3, 4])
  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:
  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. while True:
  86. await wait_for_enter()
  87. await self.controller.prepare_feeder_cell()
  88. await wait_for_enter()
  89. self.logger.info("Starting movement sequence...")
  90. await self.controller.pick_cell_from_slot(self.test_slot)
  91. await self.controller.dropoff_cell()
  92. await self.controller.pick_cell_from_feeder()
  93. cell = Cell(id=1, status=CellStatus.WAITING)
  94. await self.controller.insert_cell_to_slot(cell, self.test_slot)
  95. self.logger.info("\nPress Enter to repeat sequence (or Ctrl+C to exit)...")
  96. async def cleanup(self):
  97. self.logger.info("Cleaning up resources...")
  98. await self.controller.cleanup()
  99. self.gpio.cleanup()
  100. if __name__ == "__main__":
  101. loader_system = LoaderSystem()
  102. async def shutdown():
  103. loader_system.logger.info("Shutting down...")
  104. await loader_system.cleanup()
  105. sys.exit(0)
  106. def handle_signal(sig, frame):
  107. asyncio.get_event_loop().create_task(shutdown())
  108. signal.signal(signal.SIGINT, handle_signal)
  109. signal.signal(signal.SIGTERM, handle_signal)
  110. asyncio.run(loader_system.run())