Skip to content
Open
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
3 changes: 3 additions & 0 deletions pylabrobot/arms/__init__.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
from .precise_flex import *
from .scara import *
from .six_axis import *
from .six_axis_backend import *
from .standard import *
from .xarm6 import *
129 changes: 129 additions & 0 deletions pylabrobot/arms/six_axis.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
from typing import Dict, Optional, Union

from pylabrobot.arms.backend import AccessPattern
from pylabrobot.arms.six_axis_backend import SixAxisBackend
from pylabrobot.arms.standard import CartesianCoords
from pylabrobot.machines.machine import Machine


class SixAxisArm(Machine):
"""A 6-axis robotic arm frontend."""

def __init__(self, backend: SixAxisBackend):
super().__init__(backend=backend)
self.backend: SixAxisBackend = backend
self._in_freedrive = False

async def _ensure_not_freedrive(self):
if self._in_freedrive:
await self.end_freedrive_mode()

async def move_to(
self,
position: Union[CartesianCoords, Dict[int, float]],
**backend_kwargs,
) -> None:
"""Move the arm to a specified position in Cartesian or joint space."""
await self._ensure_not_freedrive()
return await self.backend.move_to(position, **backend_kwargs)

async def get_joint_position(self, **backend_kwargs) -> Dict[int, float]:
"""Get the current position of the arm in joint space."""
return await self.backend.get_joint_position(**backend_kwargs)

async def get_cartesian_position(self, **backend_kwargs) -> CartesianCoords:
"""Get the current position of the arm in Cartesian space."""
return await self.backend.get_cartesian_position(**backend_kwargs)

async def open_gripper(self, position: int, speed: int = 0, **backend_kwargs) -> None:
"""Open the arm's gripper.

Args:
position: Target open position (gripper-specific units).
speed: Gripper speed (0 = default/max).
"""
await self._ensure_not_freedrive()
return await self.backend.open_gripper(position=position, speed=speed, **backend_kwargs)

async def close_gripper(self, position: int, speed: int = 0, **backend_kwargs) -> None:
"""Close the arm's gripper.

Args:
position: Target close position (gripper-specific units).
speed: Gripper speed (0 = default/max).
"""
await self._ensure_not_freedrive()
return await self.backend.close_gripper(position=position, speed=speed, **backend_kwargs)

async def halt(self, **backend_kwargs) -> None:
"""Emergency stop any ongoing movement of the arm."""
await self._ensure_not_freedrive()
return await self.backend.halt(**backend_kwargs)

async def home(self, **backend_kwargs) -> None:
"""Home the arm to its default position."""
await self._ensure_not_freedrive()
return await self.backend.home(**backend_kwargs)

async def move_to_safe(self, **backend_kwargs) -> None:
"""Move the arm to a predefined safe position."""
await self._ensure_not_freedrive()
return await self.backend.move_to_safe(**backend_kwargs)

async def approach(
self,
position: Union[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
**backend_kwargs,
) -> None:
"""Move the arm to an approach position (offset from target).

Args:
position: Target position (CartesianCoords or joint position dict)
access: Access pattern defining how to approach the target.
Defaults to VerticalAccess() if not specified.
"""
await self._ensure_not_freedrive()
return await self.backend.approach(position, access=access, **backend_kwargs)

async def pick_up_resource(
self,
position: Union[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
**backend_kwargs,
) -> None:
"""Pick a resource from the specified position.

Args:
position: Target position for pickup
access: Access pattern defining how to approach and retract.
Defaults to VerticalAccess() if not specified.
"""
await self._ensure_not_freedrive()
return await self.backend.pick_up_resource(position=position, access=access, **backend_kwargs)

async def drop_resource(
self,
position: Union[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
**backend_kwargs,
) -> None:
"""Place a resource at the specified position.

Args:
position: Target position for placement
access: Access pattern defining how to approach and retract.
Defaults to VerticalAccess() if not specified.
"""
await self._ensure_not_freedrive()
return await self.backend.drop_resource(position, access=access, **backend_kwargs)

async def freedrive_mode(self, **backend_kwargs) -> None:
"""Enter freedrive mode, allowing manual movement of all joints."""
await self.backend.freedrive_mode(**backend_kwargs)
self._in_freedrive = True

async def end_freedrive_mode(self, **backend_kwargs) -> None:
"""Exit freedrive mode."""
await self.backend.end_freedrive_mode(**backend_kwargs)
self._in_freedrive = False
102 changes: 102 additions & 0 deletions pylabrobot/arms/six_axis_backend.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
from abc import ABCMeta, abstractmethod
from typing import Dict, Optional, Union

from pylabrobot.arms.backend import AccessPattern
from pylabrobot.arms.standard import CartesianCoords
from pylabrobot.machines.backend import MachineBackend


class SixAxisBackend(MachineBackend, metaclass=ABCMeta):
"""Backend for a 6-axis robotic arm."""

@abstractmethod
async def open_gripper(self, position: int, speed: int = 0) -> None:
"""Open the arm's gripper.

Args:
position: Target open position (gripper-specific units).
speed: Gripper speed (0 = default/max).
"""

@abstractmethod
async def close_gripper(self, position: int, speed: int = 0) -> None:
"""Close the arm's gripper.

Args:
position: Target close position (gripper-specific units).
speed: Gripper speed (0 = default/max).
"""

@abstractmethod
async def halt(self) -> None:
"""Emergency stop any ongoing movement of the arm."""

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

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

@abstractmethod
async def approach(
self,
position: Union[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
) -> None:
"""Move the arm to an approach position (offset from target).

Args:
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[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
) -> None:
"""Pick a resource from the specified position.

Args:
position: Target position for pickup
access: Access pattern defining how to approach and retract.
Defaults to VerticalAccess() if not specified.
"""

@abstractmethod
async def drop_resource(
self,
position: Union[CartesianCoords, Dict[int, float]],
access: Optional[AccessPattern] = None,
) -> None:
"""Place a resource at the specified position.

Args:
position: Target position for placement
access: Access pattern defining how to approach and retract.
Defaults to VerticalAccess() if not specified.
"""

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

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

@abstractmethod
async def get_cartesian_position(self) -> CartesianCoords:
"""Get the current position of the arm in Cartesian space."""

@abstractmethod
async def freedrive_mode(self) -> None:
"""Enter freedrive mode, allowing manual movement of all joints."""

@abstractmethod
async def end_freedrive_mode(self) -> None:
"""Exit freedrive mode."""
106 changes: 106 additions & 0 deletions pylabrobot/arms/six_axis_tests.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
import unittest
from unittest.mock import AsyncMock, MagicMock

from pylabrobot.arms.six_axis import SixAxisArm
from pylabrobot.arms.six_axis_backend import SixAxisBackend
from pylabrobot.arms.standard import CartesianCoords
from pylabrobot.resources import Coordinate, Rotation


class TestSixAxisArm(unittest.IsolatedAsyncioTestCase):
async def asyncSetUp(self):
self.mock_backend = MagicMock(spec=SixAxisBackend)
for method_name in [
"move_to",
"get_joint_position",
"get_cartesian_position",
"open_gripper",
"close_gripper",
"halt",
"home",
"move_to_safe",
"approach",
"pick_up_resource",
"drop_resource",
"freedrive_mode",
"end_freedrive_mode",
]:
setattr(self.mock_backend, method_name, AsyncMock())
self.arm = SixAxisArm(backend=self.mock_backend)

async def test_move_to(self):
position = CartesianCoords(
location=Coordinate(x=100, y=200, z=300), rotation=Rotation(x=0, y=0, z=0)
)
await self.arm.move_to(position)
self.mock_backend.move_to.assert_called_once_with(position)

async def test_get_joint_position(self):
await self.arm.get_joint_position()
self.mock_backend.get_joint_position.assert_called_once()

async def test_get_cartesian_position(self):
await self.arm.get_cartesian_position()
self.mock_backend.get_cartesian_position.assert_called_once()

async def test_open_gripper(self):
await self.arm.open_gripper(position=850, speed=5)
self.mock_backend.open_gripper.assert_called_once_with(position=850, speed=5)

async def test_close_gripper(self):
await self.arm.close_gripper(position=100, speed=5)
self.mock_backend.close_gripper.assert_called_once_with(position=100, speed=5)

async def test_halt(self):
await self.arm.halt()
self.mock_backend.halt.assert_called_once()

async def test_home(self):
await self.arm.home()
self.mock_backend.home.assert_called_once()

async def test_move_to_safe(self):
await self.arm.move_to_safe()
self.mock_backend.move_to_safe.assert_called_once()

async def test_approach(self):
position = CartesianCoords(
location=Coordinate(x=100, y=200, z=300), rotation=Rotation(x=0, y=0, z=0)
)
await self.arm.approach(position)
self.mock_backend.approach.assert_called_once_with(position, access=None)

async def test_pick_up_resource(self):
position = CartesianCoords(
location=Coordinate(x=100, y=200, z=300), rotation=Rotation(x=0, y=0, z=0)
)
await self.arm.pick_up_resource(position)
self.mock_backend.pick_up_resource.assert_called_once_with(position=position, access=None)

async def test_drop_resource(self):
position = CartesianCoords(
location=Coordinate(x=100, y=200, z=300), rotation=Rotation(x=0, y=0, z=0)
)
await self.arm.drop_resource(position)
self.mock_backend.drop_resource.assert_called_once_with(position, access=None)

async def test_freedrive_mode(self):
await self.arm.freedrive_mode()
self.mock_backend.freedrive_mode.assert_called_once()
self.assertTrue(self.arm._in_freedrive)

async def test_end_freedrive_mode(self):
self.arm._in_freedrive = True
await self.arm.end_freedrive_mode()
self.mock_backend.end_freedrive_mode.assert_called_once()
self.assertFalse(self.arm._in_freedrive)

async def test_auto_exit_freedrive_on_move(self):
self.arm._in_freedrive = True
position = CartesianCoords(
location=Coordinate(x=100, y=200, z=300), rotation=Rotation(x=0, y=0, z=0)
)
await self.arm.move_to(position)
self.mock_backend.end_freedrive_mode.assert_called_once()
self.assertFalse(self.arm._in_freedrive)
self.mock_backend.move_to.assert_called_once_with(position)
2 changes: 2 additions & 0 deletions pylabrobot/arms/xarm6/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
from .joints import *
from .xarm6_backend import *
Loading
Loading