Skip to content

Commit b6b5a10

Browse files
committed
use existing types in CartesianCoords
1 parent 6fad8f7 commit b6b5a10

File tree

4 files changed

+60
-34
lines changed

4 files changed

+60
-34
lines changed

pylabrobot/arms/coords.py

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22
from enum import Enum
33
from typing import Optional
44

5+
from pylabrobot.resources import Coordinate, Rotation
6+
57

68
class ElbowOrientation(Enum):
79
RIGHT = "right"
@@ -20,10 +22,6 @@ class JointCoords:
2022

2123
@dataclass
2224
class CartesianCoords:
23-
x: float
24-
y: float
25-
z: float
26-
yaw: float
27-
pitch: float
28-
roll: float
25+
location: Coordinate
26+
rotation: Rotation
2927
orientation: Optional[ElbowOrientation] = None

pylabrobot/arms/precise_flex/precise_flex_backend.py

Lines changed: 32 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,12 @@
11
from abc import ABC, abstractmethod
2-
from typing import Optional, Union
2+
from typing import Literal, Optional, Union
33

44
from pylabrobot.arms.backend import ArmBackend
55
from pylabrobot.arms.coords import CartesianCoords, ElbowOrientation, JointCoords
66
from pylabrobot.arms.precise_flex.precise_flex_api import PreciseFlexBackendApi
7+
from pylabrobot.resources import Coordinate, Rotation
8+
9+
PreciseFlexModel = Literal["pf400", "pf3400"]
710

811

912
class CoordsConverter(ABC):
@@ -55,7 +58,9 @@ def convert_to_cartesian_space(
5558
)
5659
orientation = ElbowOrientation(position[6])
5760
return CartesianCoords(
58-
position[0], position[1], position[2], position[3], position[4], position[5], orientation
61+
location=Coordinate(position[0], position[1], position[2]),
62+
rotation=Rotation(position[5], position[4], position[3]),
63+
orientation=orientation,
5964
)
6065

6166
def convert_to_joints_array(
@@ -78,12 +83,12 @@ def convert_to_cartesian_array(
7883
"""Convert a CartesianSpace object to a list of cartesian coordinates."""
7984
orientation_int = self._convert_orientation_enum_to_int(position.orientation)
8085
arr = (
81-
position.x,
82-
position.y,
83-
position.z,
84-
position.yaw,
85-
position.pitch,
86-
position.roll,
86+
position.location.x,
87+
position.location.y,
88+
position.location.z,
89+
position.rotation.yaw,
90+
position.rotation.pitch,
91+
position.rotation.roll,
8792
orientation_int,
8893
)
8994
return arr
@@ -118,7 +123,9 @@ def convert_to_cartesian_space(
118123
)
119124
orientation = ElbowOrientation(position[6])
120125
return CartesianCoords(
121-
position[0], position[1], position[2], position[3], position[4], position[5], orientation
126+
location=Coordinate(position[0], position[1], position[2]),
127+
rotation=Rotation(position[5], position[4], position[3]),
128+
orientation=orientation,
122129
)
123130

124131
def convert_to_joints_array(
@@ -141,12 +148,12 @@ def convert_to_cartesian_array(
141148
"""Convert a CartesianSpace object to a list of cartesian coordinates."""
142149
orientation_int = self._convert_orientation_enum_to_int(position.orientation)
143150
arr = (
144-
position.x,
145-
position.y,
146-
position.z,
147-
position.yaw,
148-
position.pitch,
149-
position.roll,
151+
position.location.x,
152+
position.location.y,
153+
position.location.z,
154+
position.rotation.yaw,
155+
position.rotation.pitch,
156+
position.rotation.roll,
150157
orientation_int,
151158
)
152159
return arr
@@ -164,7 +171,7 @@ def _convert_orientation_enum_to_int(self, orientation: Optional[ElbowOrientatio
164171

165172
class CoordsConverterFactory:
166173
@staticmethod
167-
def create_coords_converter(model: str) -> CoordsConverter:
174+
def create_coords_converter(model: PreciseFlexModel) -> CoordsConverter:
168175
"""Factory method to create a CoordsConverter based on the robot model."""
169176
if model == "pf400":
170177
return PreciseFlex400SpaceConverter()
@@ -176,7 +183,7 @@ def create_coords_converter(model: str) -> CoordsConverter:
176183
class PreciseFlexBackend(ArmBackend, ABC):
177184
"""Backend for the PreciseFlex robotic arm - Default to using Cartesian coordinates, some methods in Brook's TCS don't work with Joint coordinates."""
178185

179-
def __init__(self, model: str, host: str, port: int = 10100, timeout=20) -> None:
186+
def __init__(self, model: PreciseFlexModel, host: str, port: int = 10100, timeout=20) -> None:
180187
super().__init__()
181188
self.api = PreciseFlexBackendApi(host=host, port=port, timeout=timeout)
182189
self.space_converter = CoordsConverterFactory.create_coords_converter(model)
@@ -280,20 +287,20 @@ async def version(self) -> str:
280287

281288
async def approach(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
282289
"""Move the arm to a position above the specified coordinates by a certain distance."""
283-
if type(position) == JointCoords:
290+
if isinstance(position, JointCoords):
284291
joints = self.space_converter.convert_to_joints_array(position)
285292
await self._approach_j(joints, approach_height)
286-
elif type(position) == CartesianCoords:
293+
elif isinstance(position, CartesianCoords):
287294
xyz = self.space_converter.convert_to_cartesian_array(position)
288295
await self._approach_c(xyz[:-1], approach_height, xyz[-1])
289296
else:
290297
raise ValueError("Position must be of type JointSpace or CartesianSpace.")
291298

292299
async def pick_plate(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
293300
"""Pick a plate from the specified position."""
294-
if type(position) == JointCoords:
301+
if isinstance(position, JointCoords):
295302
raise ValueError("pick_plate only supports CartesianCoords for PreciseFlex.")
296-
elif type(position) == CartesianCoords:
303+
elif isinstance(position, CartesianCoords):
297304
xyz = self.space_converter.convert_to_cartesian_array(position)
298305
await self._pick_plate_c(xyz[:-1], approach_height, xyz[-1])
299306
else:
@@ -303,20 +310,20 @@ async def place_plate(
303310
self, position: Union[CartesianCoords, JointCoords], approach_height: float
304311
):
305312
"""Place a plate at the specified position."""
306-
if type(position) == JointCoords:
313+
if isinstance(position, JointCoords):
307314
raise ValueError("place_plate only supports CartesianCoords for PreciseFlex.")
308-
elif type(position) == CartesianCoords:
315+
elif isinstance(position, CartesianCoords):
309316
xyz = self.space_converter.convert_to_cartesian_array(position)
310317
await self._place_plate_c(xyz[:-1], approach_height, xyz[-1])
311318
else:
312319
raise ValueError("Position must be of type JointSpace or CartesianSpace.")
313320

314321
async def move_to(self, position: Union[CartesianCoords, JointCoords]):
315322
"""Move the arm to a specified position in 3D space."""
316-
if type(position) == JointCoords:
323+
if isinstance(position, JointCoords):
317324
joints = self.space_converter.convert_to_joints_array(position)
318325
await self._move_to_j(joints)
319-
elif type(position) == CartesianCoords:
326+
elif isinstance(position, CartesianCoords):
320327
xyz = self.space_converter.convert_to_cartesian_array(position)
321328
await self._move_to_c(xyz[:-1], xyz[-1])
322329
else:

pylabrobot/arms/precise_flex/precise_flex_backend_tests.py

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
from pylabrobot.arms.coords import CartesianCoords, ElbowOrientation, JointCoords
66
from pylabrobot.arms.precise_flex.precise_flex_backend import PreciseFlexBackend
7+
from pylabrobot.resources import Coordinate, Rotation
78

89

910
@pytest.mark.hardware # include/exclude via "pytest -m hardware"
@@ -21,17 +22,25 @@ class PreciseFlexBackendHardwareTests(unittest.IsolatedAsyncioTestCase):
2122
TEST_PARAMETER_ID = 17018
2223
TEST_SIGNAL_ID = 20064
2324

24-
SAFE_LOCATION_C = CartesianCoords(175, 0, 169.994, -0.001, 90, 180, ElbowOrientation.RIGHT)
25+
SAFE_LOCATION_C = CartesianCoords(
26+
location=Coordinate(175, 0, 169.994),
27+
rotation=Rotation(180, 90, -0.001),
28+
orientation=ElbowOrientation.RIGHT,
29+
)
2530
SAFE_LOCATION_J = JointCoords(0, 170.003, 0, 180, -180, 75.486)
2631

2732
TEST_LOCATION_J_LEFT = JointCoords(0, 169.932, 16.883, 230.942, -224.288, 75.662)
2833
TEST_LOCATION_C_LEFT = CartesianCoords(
29-
328.426, -115.219, 169.932, 23.537, 90, 180, ElbowOrientation.LEFT
34+
location=Coordinate(328.426, -115.219, 169.932),
35+
rotation=Rotation(180, 90, 23.537),
36+
orientation=ElbowOrientation.LEFT,
3037
)
3138

3239
TEST_LOCATION_J_RIGHT = JointCoords(0, 169.968, -4.238, 117.915, -100.062, 75.668)
3340
TEST_LOCATION_C_RIGHT = CartesianCoords(
34-
342.562, 280.484, 169.969, 13.612, 90, 180, ElbowOrientation.RIGHT
41+
location=Coordinate(342.562, 280.484, 169.969),
42+
rotation=Rotation(180, 90, 13.612),
43+
orientation=ElbowOrientation.RIGHT,
3544
)
3645

3746
async def asyncSetUp(self):

pylabrobot/resources/rotation.py

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,3 +68,15 @@ def deserialize(data) -> "Rotation":
6868

6969
def __repr__(self) -> str:
7070
return self.__str__()
71+
72+
@property
73+
def roll(self) -> float:
74+
return self.x
75+
76+
@property
77+
def pitch(self) -> float:
78+
return self.y
79+
80+
@property
81+
def yaw(self) -> float:
82+
return self.z

0 commit comments

Comments
 (0)