|
|
@@ -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}")
|