Skip to content

Commit a1db74d

Browse files
committed
Merge branch 'dev-precise-flex-pf400' into io-socket-refactor
2 parents 6638d06 + 2624bf7 commit a1db74d

File tree

16 files changed

+7012
-0
lines changed

16 files changed

+7012
-0
lines changed

_typos.toml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,11 @@ PN = "PN"
2020
tro = "tro"
2121
FO = "FO"
2222
UE = "UE"
23+
commutated = "commutated"
24+
commutating = "commutating"
25+
DOUT = "DOUT"
26+
inconsistence = "inconsistence" # ignored to match with preciseflex documentation typo
27+
mis = "mis" # ignored to match with preciseflex documentation typo
2328

2429
[files]
2530
extend-exclude = [

pylabrobot/arms/__init__.py

Whitespace-only changes.

pylabrobot/arms/arm.py

Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
from typing import Optional, Union
2+
3+
from pylabrobot.arms.backend import AccessPattern, ArmBackend
4+
from pylabrobot.arms.coords import CartesianCoords, JointCoords
5+
from pylabrobot.machines.machine import Machine
6+
7+
8+
class Arm(Machine):
9+
"""A robotic arm."""
10+
11+
def __init__(self, backend: ArmBackend):
12+
super().__init__(backend=backend)
13+
self.backend: ArmBackend = backend
14+
15+
async def move_to(self, position: Union[CartesianCoords, JointCoords]):
16+
"""Move the arm to a specified position in 3D space."""
17+
return self.backend.move_to(position)
18+
19+
async def get_joint_position(self) -> JointCoords:
20+
"""Get the current position of the arm in 3D space."""
21+
return await self.backend.get_joint_position()
22+
23+
async def get_cartesian_position(self) -> CartesianCoords:
24+
"""Get the current position of the arm in 3D space."""
25+
return await self.backend.get_cartesian_position()
26+
27+
async def set_speed(self, speed: float):
28+
"""Set the speed of the arm's movement."""
29+
return await self.backend.set_speed(speed)
30+
31+
async def get_speed(self) -> float:
32+
"""Get the current speed of the arm's movement."""
33+
return await self.backend.get_speed()
34+
35+
async def open_gripper(self):
36+
"""Open the arm's gripper."""
37+
return await self.backend.open_gripper()
38+
39+
async def close_gripper(self):
40+
"""Close the arm's gripper."""
41+
return await self.backend.close_gripper()
42+
43+
async def is_gripper_closed(self) -> bool:
44+
"""Check if the gripper is currently closed."""
45+
return await self.backend.is_gripper_closed()
46+
47+
async def halt(self):
48+
"""Stop any ongoing movement of the arm."""
49+
return await self.backend.halt()
50+
51+
async def home(self):
52+
"""Home the arm to its default position."""
53+
return await self.backend.home()
54+
55+
async def move_to_safe(self):
56+
"""Move the arm to a predefined safe position."""
57+
return await self.backend.move_to_safe()
58+
59+
async def approach(
60+
self,
61+
position: Union[CartesianCoords, JointCoords],
62+
access: Optional[AccessPattern] = None
63+
):
64+
"""Move the arm to an approach position (offset from target).
65+
66+
Args:
67+
position: Target position (CartesianCoords or JointCoords)
68+
access: Access pattern defining how to approach the target.
69+
Defaults to VerticalAccess() if not specified.
70+
"""
71+
return await self.backend.approach(position, access)
72+
73+
async def pick_plate(
74+
self,
75+
position: Union[CartesianCoords, JointCoords],
76+
access: Optional[AccessPattern] = None
77+
):
78+
"""Pick a plate from the specified position.
79+
80+
Args:
81+
position: Target position for pickup
82+
access: Access pattern defining how to approach and retract.
83+
Defaults to VerticalAccess() if not specified.
84+
"""
85+
return await self.backend.pick_plate(position, access)
86+
87+
async def place_plate(
88+
self,
89+
position: Union[CartesianCoords, JointCoords],
90+
access: Optional[AccessPattern] = None
91+
):
92+
"""Place a plate at the specified position.
93+
94+
Args:
95+
position: Target position for placement
96+
access: Access pattern defining how to approach and retract.
97+
Defaults to VerticalAccess() if not specified.
98+
"""
99+
return await self.backend.place_plate(position, access)

pylabrobot/arms/backend.py

Lines changed: 156 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,156 @@
1+
from abc import ABCMeta, abstractmethod
2+
from dataclasses import dataclass
3+
from typing import Optional, Union
4+
5+
from pylabrobot.arms.coords import CartesianCoords, JointCoords
6+
from pylabrobot.machines.backend import MachineBackend
7+
8+
9+
@dataclass
10+
class VerticalAccess:
11+
"""Access location from above (most common pattern for stacks and tube racks).
12+
13+
This access pattern is used when approaching a location from above, such as
14+
picking from a plate stack or tube rack on the deck.
15+
16+
Args:
17+
approach_height_mm: Height above the target position to move to before
18+
descending to grip (default: 100mm)
19+
clearance_mm: Vertical distance to retract after gripping before lateral
20+
movement (default: 100mm)
21+
gripper_offset_mm: Additional vertical offset added when holding a plate,
22+
accounts for gripper thickness (default: 10mm)
23+
"""
24+
approach_height_mm: float = 100
25+
clearance_mm: float = 100
26+
gripper_offset_mm: float = 10
27+
28+
29+
@dataclass
30+
class HorizontalAccess:
31+
"""Access location from the side (for hotel-style plate carriers).
32+
33+
This access pattern is used when approaching a location horizontally, such as
34+
accessing plates in a hotel-style storage system.
35+
36+
Args:
37+
approach_distance_mm: Horizontal distance in front of the target to stop
38+
before moving in to grip (default: 50mm)
39+
clearance_mm: Horizontal distance to retract after gripping before lifting
40+
(default: 50mm)
41+
lift_height_mm: Vertical distance to lift the plate after horizontal retract,
42+
before lateral movement (default: 100mm)
43+
gripper_offset_mm: Additional vertical offset added when holding a plate,
44+
accounts for gripper thickness (default: 10mm)
45+
"""
46+
approach_distance_mm: float = 50
47+
clearance_mm: float = 50
48+
lift_height_mm: float = 100
49+
gripper_offset_mm: float = 10
50+
51+
52+
AccessPattern = Union[VerticalAccess, HorizontalAccess]
53+
54+
55+
class ArmBackend(MachineBackend, metaclass=ABCMeta):
56+
"""Backend for a robotic arm"""
57+
58+
@abstractmethod
59+
async def set_speed(self, speed: float):
60+
"""Set the speed percentage of the arm's movement (0-100)."""
61+
...
62+
63+
@abstractmethod
64+
async def get_speed(self) -> float:
65+
"""Get the current speed percentage of the arm's movement."""
66+
...
67+
68+
@abstractmethod
69+
async def open_gripper(self):
70+
"""Open the arm's gripper."""
71+
...
72+
73+
@abstractmethod
74+
async def close_gripper(self):
75+
"""Close the arm's gripper."""
76+
...
77+
78+
@abstractmethod
79+
async def is_gripper_closed(self) -> bool:
80+
"""Check if the gripper is currently closed."""
81+
...
82+
83+
@abstractmethod
84+
async def halt(self):
85+
"""Stop any ongoing movement of the arm."""
86+
...
87+
88+
@abstractmethod
89+
async def home(self):
90+
"""Home the arm to its default position."""
91+
...
92+
93+
@abstractmethod
94+
async def move_to_safe(self):
95+
"""Move the arm to a predefined safe position."""
96+
...
97+
98+
@abstractmethod
99+
async def approach(
100+
self,
101+
position: Union[CartesianCoords, JointCoords],
102+
access: Optional[AccessPattern] = None
103+
):
104+
"""Move the arm to an approach position (offset from target).
105+
106+
Args:
107+
position: Target position (CartesianCoords or JointCoords)
108+
access: Access pattern defining how to approach the target.
109+
Defaults to VerticalAccess() if not specified.
110+
"""
111+
...
112+
113+
@abstractmethod
114+
async def pick_plate(
115+
self,
116+
position: Union[CartesianCoords, JointCoords],
117+
access: Optional[AccessPattern] = None
118+
):
119+
"""Pick a plate from the specified position.
120+
121+
Args:
122+
position: Target position for pickup
123+
access: Access pattern defining how to approach and retract.
124+
Defaults to VerticalAccess() if not specified.
125+
"""
126+
...
127+
128+
@abstractmethod
129+
async def place_plate(
130+
self,
131+
position: Union[CartesianCoords, JointCoords],
132+
access: Optional[AccessPattern] = None
133+
):
134+
"""Place a plate at the specified position.
135+
136+
Args:
137+
position: Target position for placement
138+
access: Access pattern defining how to approach and retract.
139+
Defaults to VerticalAccess() if not specified.
140+
"""
141+
...
142+
143+
@abstractmethod
144+
async def move_to(self, position: Union[CartesianCoords, JointCoords]):
145+
"""Move the arm to a specified position in 3D space."""
146+
...
147+
148+
@abstractmethod
149+
async def get_joint_position(self) -> JointCoords:
150+
"""Get the current position of the arm in 3D space."""
151+
...
152+
153+
@abstractmethod
154+
async def get_cartesian_position(self) -> CartesianCoords:
155+
"""Get the current position of the arm in 3D space."""
156+
...

pylabrobot/arms/coords.py

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
from dataclasses import dataclass
2+
from enum import Enum
3+
from typing import Optional
4+
5+
from pylabrobot.resources import Coordinate, Rotation
6+
7+
8+
class ElbowOrientation(Enum):
9+
RIGHT = "right"
10+
LEFT = "left"
11+
12+
13+
@dataclass
14+
class JointCoords:
15+
rail: float
16+
base: float
17+
shoulder: float
18+
elbow: float
19+
wrist: float
20+
gripper: float
21+
22+
23+
@dataclass
24+
class CartesianCoords:
25+
location: Coordinate
26+
rotation: Rotation
27+
orientation: Optional[ElbowOrientation] = None

pylabrobot/arms/precise_flex/__init__.py

Whitespace-only changes.

0 commit comments

Comments
 (0)