Skip to content

Commit 62ba6c0

Browse files
committed
support backend kwargs
1 parent dbb024a commit 62ba6c0

File tree

1 file changed

+31
-24
lines changed

1 file changed

+31
-24
lines changed

pylabrobot/arms/scara.py

Lines changed: 31 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -14,46 +14,51 @@ def __init__(self, backend: SCARABackend):
1414
super().__init__(backend=backend)
1515
self.backend: SCARABackend = backend
1616

17-
async def move_to(self, position: Union[PreciseFlexCartesianCoords, Iterable[float]]):
17+
async def move_to(
18+
self,
19+
position: Union[PreciseFlexCartesianCoords, Iterable[float]],
20+
**backend_kwargs,
21+
) -> None:
1822
"""Move the arm to a specified position in 3D space or joint space."""
1923
if isinstance(position, Iterable) and not isinstance(position, list):
2024
position = list(position)
21-
return await self.backend.move_to(position)
25+
return await self.backend.move_to(position, **backend_kwargs)
2226

23-
async def get_joint_position(self) -> JointCoords:
27+
async def get_joint_position(self, **backend_kwargs) -> JointCoords:
2428
"""Get the current position of the arm in joint space."""
25-
return await self.backend.get_joint_position()
29+
return await self.backend.get_joint_position(**backend_kwargs)
2630

27-
async def get_cartesian_position(self) -> PreciseFlexCartesianCoords:
31+
async def get_cartesian_position(self, **backend_kwargs) -> PreciseFlexCartesianCoords:
2832
"""Get the current position of the arm in 3D space."""
29-
return await self.backend.get_cartesian_position()
33+
return await self.backend.get_cartesian_position(**backend_kwargs)
3034

31-
async def open_gripper(self):
32-
return await self.backend.open_gripper()
35+
async def open_gripper(self, **backend_kwargs) -> None:
36+
return await self.backend.open_gripper(**backend_kwargs)
3337

34-
async def close_gripper(self):
35-
return await self.backend.close_gripper()
38+
async def close_gripper(self, **backend_kwargs) -> None:
39+
return await self.backend.close_gripper(**backend_kwargs)
3640

37-
async def is_gripper_closed(self) -> bool:
38-
return await self.backend.is_gripper_closed()
41+
async def is_gripper_closed(self, **backend_kwargs) -> bool:
42+
return await self.backend.is_gripper_closed(**backend_kwargs)
3943

40-
async def halt(self):
44+
async def halt(self, **backend_kwargs) -> None:
4145
"""Stop any ongoing movement of the arm."""
42-
return await self.backend.halt()
46+
return await self.backend.halt(**backend_kwargs)
4347

44-
async def home(self):
48+
async def home(self, **backend_kwargs) -> None:
4549
"""Home the arm to its default position."""
46-
return await self.backend.home()
50+
return await self.backend.home(**backend_kwargs)
4751

48-
async def move_to_safe(self):
52+
async def move_to_safe(self, **backend_kwargs) -> None:
4953
"""Move the arm to a predefined safe position."""
50-
return await self.backend.move_to_safe()
54+
return await self.backend.move_to_safe(**backend_kwargs)
5155

5256
async def approach(
5357
self,
5458
position: Union[PreciseFlexCartesianCoords, JointCoords],
5559
access: Optional[AccessPattern] = None,
56-
):
60+
**backend_kwargs,
61+
) -> None:
5762
"""Move the arm to an approach position (offset from target).
5863
5964
Args:
@@ -62,13 +67,14 @@ async def approach(
6267
"""
6368
if isinstance(position, Iterable) and not isinstance(position, list):
6469
position = list(position)
65-
return await self.backend.approach(position, access)
70+
return await self.backend.approach(position, access=access, **backend_kwargs)
6671

6772
async def pick_plate(
6873
self,
6974
position: Union[PreciseFlexCartesianCoords, JointCoords],
7075
access: Optional[AccessPattern] = None,
71-
):
76+
**backend_kwargs,
77+
) -> None:
7278
"""Pick a plate from the specified position.
7379
7480
Args:
@@ -77,13 +83,14 @@ async def pick_plate(
7783
"""
7884
if isinstance(position, Iterable) and not isinstance(position, list):
7985
position = list(position)
80-
return await self.backend.pick_plate(position, access)
86+
return await self.backend.pick_plate(position, access=access, **backend_kwargs)
8187

8288
async def place_plate(
8389
self,
8490
position: Union[PreciseFlexCartesianCoords, JointCoords],
8591
access: Optional[AccessPattern] = None,
86-
):
92+
**backend_kwargs,
93+
) -> None:
8794
"""Place a plate at the specified position.
8895
8996
Args:
@@ -92,4 +99,4 @@ async def place_plate(
9299
"""
93100
if isinstance(position, Iterable) and not isinstance(position, list):
94101
position = list(position)
95-
return await self.backend.place_plate(position, access)
102+
return await self.backend.place_plate(position, access=access, **backend_kwargs)

0 commit comments

Comments
 (0)