Skip to content

Commit f77f301

Browse files
committed
forgot
1 parent 7bf67c4 commit f77f301

File tree

3 files changed

+96
-2
lines changed

3 files changed

+96
-2
lines changed

pylabrobot/arms/backend.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
from abc import ABCMeta, abstractmethod
22
from dataclasses import dataclass
3-
from typing import List, Optional, Union
3+
from typing import Optional, Union
44

55
from pylabrobot.arms.precise_flex.coords import PreciseFlexCartesianCoords
66
from pylabrobot.arms.standard import JointCoords

pylabrobot/arms/precise_flex/precise_flex_backend.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@
55
from pylabrobot.arms.backend import (
66
AccessPattern,
77
HorizontalAccess,
8-
JointCoords,
98
SCARABackend,
109
VerticalAccess,
1110
)

pylabrobot/arms/scara.py

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

0 commit comments

Comments
 (0)