Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
39 commits
Select commit Hold shift + click to select a range
0446c90
Adds driver for PreciseFlex PF400. Adds TCP connection for io.
miikee Jul 23, 2025
04a6801
Adds Arm Machine class
miikee Jul 24, 2025
bdef716
Adds open_gripper and close_gripper methods to ArmBackend. Add ... t…
miikee Jul 24, 2025
cc2efe8
Add open_gripper and close_gripper methods to Arm class
miikee Jul 24, 2025
db70802
Adds untested warning to PreciseFlexBackend
miikee Jul 24, 2025
469b71a
Adds default port for precise flex arm robot 1
miikee Jul 24, 2025
afbbf85
WIP: Large addition of preciseflex backend api and robot_testing_script
miikee Sep 5, 2025
5ba817a
WIP: change from pytest -> unittest
miikee Sep 5, 2025
57683ac
Rename files
miikee Sep 5, 2025
3ea3452
Add __init__ for packages
miikee Sep 5, 2025
2346d0e
WIP changes to Precise Flex test including indention fixes, remove re…
miikee Sep 5, 2025
a4fda8e
Comment out testing setting mode to verbose mode
miikee Sep 5, 2025
c3c47b6
Refactor signal and location configuration methods for clarity and va…
miikee Sep 5, 2025
b24fb11
Add additional movements and gripper methods to PreciseFlex backend; …
miikee Sep 15, 2025
f66f645
Renames precise flex api files
miikee Sep 15, 2025
8b0fe6a
Rename test class for PreciseFlex API and cleanup imports
miikee Sep 15, 2025
7a7a06e
Adds a test file for the PreciseFlex backend
miikee Sep 15, 2025
37c2f2a
Edit zero_torque and set_pallet_index commands; WIP editting pallet c…
miikee Sep 17, 2025
cae5d98
Change to add preservation and restoration to the test setup and tear…
miikee Sep 17, 2025
a38a209
Add comment about cartesian and joint coords
miikee Sep 17, 2025
30c1cfe
Applicable test all working on the PreciseFlex API
miikee Sep 18, 2025
92a841c
Swap to power on robot before attach in test
miikee Sep 18, 2025
d8da11b
Fix in exit() command in api to not parse reply since ther ewon't be …
miikee Sep 18, 2025
a3c883a
update api to use 6 joints instead of 7
miikee Sep 19, 2025
6d4cb49
Edit PreciseFlex API and backend to support Cartesian and Joint coord…
miikee Sep 19, 2025
183ff3a
Correct tests for array value length changes, add restoration for pro…
miikee Sep 19, 2025
e17bcc2
Adds 'hardware' pytest marker to robot integration tests and updates …
miikee Sep 24, 2025
346c017
Refactor Arm class to support Cartesian and Joint coordinates; update…
miikee Sep 24, 2025
8a9414d
Move Cartesian and Joint coordinate models to their own file
miikee Sep 24, 2025
6998d38
Format fixes
miikee Sep 24, 2025
edaa21b
Fix f-string checks and fix bare excepts
miikee Sep 24, 2025
96fa535
Adds a few acceptable typos to the typo file
miikee Sep 24, 2025
c15c5a2
Switches 'match' statement to an 'if' statement
miikee Sep 24, 2025
c4c8c66
Refactor type hints to use Union for position parameters and update O…
miikee Sep 24, 2025
de6f753
Fromatting fix
miikee Sep 24, 2025
3cac650
Refactor type hints to use Optional for parameters in arm and precise…
miikee Sep 24, 2025
224ef7b
Lint formatting
miikee Sep 24, 2025
bc5d437
Add return type hint to send_command method in PreciseFlexBackendApi
miikee Sep 24, 2025
d69bebd
Convert test_values["straight"] to bool to enusre type checking passes
miikee Sep 24, 2025
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
5 changes: 5 additions & 0 deletions _typos.toml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,11 @@ PN = "PN"
tro = "tro"
FO = "FO"
UE = "UE"
commutated = "commutated"
commutating = "commutating"
DOUT = "DOUT"
inconsistence = "inconsistence" # ignored to match with preciseflex documentation typo
mis = "mis" # ignored to match with preciseflex documentation typo

[files]
extend-exclude = [
Expand Down
Empty file added pylabrobot/arms/__init__.py
Empty file.
71 changes: 71 additions & 0 deletions pylabrobot/arms/arm.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
from typing import Union

from pylabrobot.arms.backend import ArmBackend
from pylabrobot.arms.coords import CartesianCoords, JointCoords
from pylabrobot.machines.machine import Machine


class Arm(Machine):
"""A robotic arm."""

def __init__(self, backend: ArmBackend):
super().__init__(backend=backend)
self.backend: ArmBackend = backend

async def move_to(self, position: Union[CartesianCoords, JointCoords]):
"""Move the arm to a specified position in 3D space."""
return self.backend.move_to(position)

async def get_joint_position(self) -> JointCoords:
"""Get the current position of the arm in 3D space."""
return await self.backend.get_joint_position()

async def get_cartesian_position(self) -> CartesianCoords:
"""Get the current position of the arm in 3D space."""
return await self.backend.get_cartesian_position()

async def set_speed(self, speed: float):
"""Set the speed of the arm's movement."""
return await self.backend.set_speed(speed)

async def get_speed(self) -> float:
"""Get the current speed of the arm's movement."""
return await self.backend.get_speed()

async def open_gripper(self):
"""Open the arm's gripper."""
return await self.backend.open_gripper()

async def close_gripper(self):
"""Close the arm's gripper."""
return await self.backend.close_gripper()

async def is_gripper_closed(self) -> bool:
"""Check if the gripper is currently closed."""
return await self.backend.is_gripper_closed()

async def halt(self):
"""Stop any ongoing movement of the arm."""
return await self.backend.halt()

async def home(self):
"""Home the arm to its default position."""
return await self.backend.home()

async def move_to_safe(self):
"""Move the arm to a predefined safe position."""
return await self.backend.move_to_safe()

async def approach(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
"""Move the arm to a position above the specified coordinates by a certain distance."""
return await self.backend.approach(position, approach_height)

async def pick_plate(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
"""Pick a plate from the specified position."""
return await self.backend.pick_plate(position, approach_height)

async def place_plate(
self, position: Union[CartesianCoords, JointCoords], approach_height: float
):
"""Place a plate at the specified position."""
return await self.backend.place_plate(position, approach_height)
81 changes: 81 additions & 0 deletions pylabrobot/arms/backend.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
from abc import ABCMeta, abstractmethod
from typing import Union

from pylabrobot.arms.coords import CartesianCoords, JointCoords
from pylabrobot.machines.backend import MachineBackend


class ArmBackend(MachineBackend, metaclass=ABCMeta):
"""Backend for a robotic arm"""

@abstractmethod
async def set_speed(self, speed: float):
"""Set the speed percentage of the arm's movement (0-100)."""
...

@abstractmethod
async def get_speed(self) -> float:
"""Get the current speed percentage of the arm's movement."""
...

@abstractmethod
async def open_gripper(self):
"""Open the arm's gripper."""
...

@abstractmethod
async def close_gripper(self):
"""Close the arm's gripper."""
...

@abstractmethod
async def is_gripper_closed(self) -> bool:
"""Check if the gripper is currently closed."""
...

@abstractmethod
async def halt(self):
"""Stop any ongoing movement of the arm."""
...

@abstractmethod
async def home(self):
"""Home the arm to its default position."""
...

@abstractmethod
async def move_to_safe(self):
"""Move the arm to a predefined safe position."""
...

@abstractmethod
async def approach(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
"""Move the arm to a position above the specified coordinates by a certain distance."""
...

@abstractmethod
async def pick_plate(self, position: Union[CartesianCoords, JointCoords], approach_height: float):
"""Pick a plate from the specified position."""
...

@abstractmethod
async def place_plate(
self, position: Union[CartesianCoords, JointCoords], approach_height: float
):
"""Place a plate at the specified position."""
...

@abstractmethod
async def move_to(self, position: Union[CartesianCoords, JointCoords]):
"""Move the arm to a specified position in 3D space."""
...

@abstractmethod
async def get_joint_position(self) -> JointCoords:
"""Get the current position of the arm in 3D space."""
...

@abstractmethod
async def get_cartesian_position(self) -> CartesianCoords:
"""Get the current position of the arm in 3D space."""
...
29 changes: 29 additions & 0 deletions pylabrobot/arms/coords.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
from dataclasses import dataclass
from enum import Enum
from typing import Optional


class ElbowOrientation(Enum):
RIGHT = "right"
LEFT = "left"


@dataclass
class JointCoords:
rail: float
base: float
shoulder: float
elbow: float
wrist: float
gripper: float


@dataclass
class CartesianCoords:
x: float
y: float
z: float
yaw: float
pitch: float
roll: float
orientation: Optional[ElbowOrientation] = None
Empty file.
Loading