22from dataclasses import dataclass
33from typing import List , Optional , Union
44
5- from pylabrobot .arms .precise_flex .coords import CartesianCoords
5+ from pylabrobot .arms .precise_flex .coords import PreciseFlexCartesianCoords
66from pylabrobot .arms .standard import JointCoords
77from pylabrobot .machines .backend import MachineBackend
88
@@ -55,7 +55,7 @@ class HorizontalAccess:
5555AccessPattern = Union [VerticalAccess , HorizontalAccess ]
5656
5757
58- class ArmBackend (MachineBackend , metaclass = ABCMeta ):
58+ class SCARABackend (MachineBackend , metaclass = ABCMeta ):
5959 """Backend for a robotic arm"""
6060
6161 @abstractmethod
@@ -90,7 +90,9 @@ async def move_to_safe(self):
9090
9191 @abstractmethod
9292 async def approach (
93- self , position : Union [CartesianCoords , JointCoords ], access : Optional [AccessPattern ] = None
93+ self ,
94+ position : Union [PreciseFlexCartesianCoords , JointCoords ],
95+ access : Optional [AccessPattern ] = None ,
9496 ):
9597 """Move the arm to an approach position (offset from target).
9698
@@ -103,7 +105,9 @@ async def approach(
103105
104106 @abstractmethod
105107 async def pick_plate (
106- self , position : Union [CartesianCoords , JointCoords ], access : Optional [AccessPattern ] = None
108+ self ,
109+ position : Union [PreciseFlexCartesianCoords , JointCoords ],
110+ access : Optional [AccessPattern ] = None ,
107111 ):
108112 """Pick a plate from the specified position.
109113
@@ -116,7 +120,9 @@ async def pick_plate(
116120
117121 @abstractmethod
118122 async def place_plate (
119- self , position : Union [CartesianCoords , JointCoords ], access : Optional [AccessPattern ] = None
123+ self ,
124+ position : Union [PreciseFlexCartesianCoords , JointCoords ],
125+ access : Optional [AccessPattern ] = None ,
120126 ):
121127 """Place a plate at the specified position.
122128
@@ -128,7 +134,7 @@ async def place_plate(
128134 ...
129135
130136 @abstractmethod
131- async def move_to (self , position : Union [CartesianCoords , JointCoords ]):
137+ async def move_to (self , position : Union [PreciseFlexCartesianCoords , JointCoords ]):
132138 """Move the arm to a specified position in 3D space."""
133139 ...
134140
@@ -138,6 +144,6 @@ async def get_joint_position(self) -> JointCoords:
138144 ...
139145
140146 @abstractmethod
141- async def get_cartesian_position (self ) -> CartesianCoords :
147+ async def get_cartesian_position (self ) -> PreciseFlexCartesianCoords :
142148 """Get the current position of the arm in 3D space."""
143149 ...
0 commit comments