Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
"from pylabrobot.arms.precise_flex.pf_400 import PreciseFlex400Backend\n",
"\n",
"from pylabrobot.arms.precise_flex.coords import PreciseFlexCartesianCoords\n",
"from pylabrobot.arms.precise_flex.joints import PreciseFlexJointCoords\n",
"from pylabrobot.arms.precise_flex.joints import PFAxis\n",
"from pylabrobot.resources import Coordinate, Rotation"
]
},
Expand Down Expand Up @@ -144,14 +144,14 @@
"metadata": {},
"outputs": [],
"source": [
"location = PreciseFlexJointCoords(\n",
" base=99.981,\n",
" shoulder=-36.206,\n",
" elbow=83.063,\n",
" wrist=-331.7,\n",
" gripper=126.084,\n",
" rail=0.0\n",
")\n",
"location = {\n",
" PFAxis.BASE: 99.981,\n",
" PFAxis.SHOULDER: -36.206,\n",
" PFAxis.ELBOW: 83.063,\n",
" PFAxis.WRIST: -331.7,\n",
" PFAxis.GRIPPER: 126.084,\n",
" PFAxis.RAIL: 0.0,\n",
"}\n",
"await arm.move_to(location)"
]
},
Expand Down
15 changes: 7 additions & 8 deletions pylabrobot/arms/backend.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
from abc import ABCMeta, abstractmethod
from dataclasses import dataclass
from typing import Optional, Union
from typing import Dict, Optional, Union

from pylabrobot.arms.precise_flex.coords import PreciseFlexCartesianCoords
from pylabrobot.arms.standard import JointCoords
from pylabrobot.machines.backend import MachineBackend


Expand Down Expand Up @@ -78,20 +77,20 @@ async def move_to_safe(self) -> None:
@abstractmethod
async def approach(
self,
position: Union[PreciseFlexCartesianCoords, JointCoords],
position: Union[PreciseFlexCartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
) -> None:
"""Move the arm to an approach position (offset from target).

Args:
position: Target position (CartesianCoords or JointCoords)
position: Target position (CartesianCoords or joint position dict)
access: Access pattern defining how to approach the target. Defaults to VerticalAccess() if not specified.
"""

@abstractmethod
async def pick_up_resource(
self,
position: Union[PreciseFlexCartesianCoords, JointCoords],
position: Union[PreciseFlexCartesianCoords, Dict[int, float]],
plate_width: float,
access: Optional[AccessPattern] = None,
) -> None:
Expand All @@ -105,7 +104,7 @@ async def pick_up_resource(
@abstractmethod
async def drop_resource(
self,
position: Union[PreciseFlexCartesianCoords, JointCoords],
position: Union[PreciseFlexCartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
) -> None:
"""Place a plate at the specified position.
Expand All @@ -116,11 +115,11 @@ async def drop_resource(
"""

@abstractmethod
async def move_to(self, position: Union[PreciseFlexCartesianCoords, JointCoords]) -> None:
async def move_to(self, position: Union[PreciseFlexCartesianCoords, Dict[int, float]]) -> None:
"""Move the arm to a specified position in 3D space or in joint space."""

@abstractmethod
async def get_joint_position(self) -> JointCoords:
async def get_joint_position(self) -> Dict[int, float]:
"""Get the current position of the arm in joint space."""

@abstractmethod
Expand Down
30 changes: 8 additions & 22 deletions pylabrobot/arms/precise_flex/joints.py
Original file line number Diff line number Diff line change
@@ -1,24 +1,10 @@
from dataclasses import dataclass
from typing import Iterator
from enum import IntEnum


@dataclass
class PreciseFlexJointCoords:
base: float
shoulder: float
elbow: float
wrist: float
gripper: float
rail: float = 0

def __iter__(self) -> Iterator[float]:
return iter(
[
self.rail,
self.base,
self.shoulder,
self.elbow,
self.wrist,
self.gripper,
]
)
class PFAxis(IntEnum):
BASE = 1
SHOULDER = 2
ELBOW = 3
WRIST = 4
GRIPPER = 5
RAIL = 6
Loading