Skip to content

Commit

Permalink
refactor(api): wire protocol engine pick_up_tip to new hardware contr…
Browse files Browse the repository at this point in the history
…ol function (#15469)
  • Loading branch information
caila-marashaj authored Jun 25, 2024
1 parent 4a45de9 commit cdbc6c1
Show file tree
Hide file tree
Showing 11 changed files with 153 additions and 27 deletions.
43 changes: 39 additions & 4 deletions api/src/opentrons/hardware_control/api.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@
RobotCalibration,
)
from .protocols import HardwareControlInterface
from .instruments.ot2.pipette_handler import PipetteHandlerProvider, PickUpTipSpec
from .instruments.ot2.pipette_handler import PipetteHandlerProvider
from .instruments.ot2.instrument_calibration import load_pipette_offset
from .motion_utilities import (
target_position_from_absolute,
Expand Down Expand Up @@ -1155,8 +1155,21 @@ async def update_nozzle_configuration_for_mount(
async def tip_pickup_moves(
self,
mount: top_types.Mount,
spec: PickUpTipSpec,
presses: Optional[int] = None,
increment: Optional[float] = None,
) -> None:
spec, _ = self.plan_check_pick_up_tip(
mount=mount, presses=presses, increment=increment
)
self._backend.set_active_current(spec.plunger_currents)
target_absolute = target_position_from_plunger(
mount, spec.plunger_prep_pos, self._current_position
)
await self._move(
target_absolute,
home_flagged_axes=False,
)

for press in spec.presses:
with self._backend.save_current():
self._backend.set_active_current(press.current)
Expand All @@ -1176,6 +1189,11 @@ async def tip_pickup_moves(

await self.retract(mount, spec.retract_target)

def cache_tip(self, mount: top_types.Mount, tip_length: float) -> None:
instrument = self.get_pipette(mount)
instrument.add_tip(tip_length=tip_length)
instrument.set_current_volume(0)

async def pick_up_tip(
self,
mount: top_types.Mount,
Expand All @@ -1189,7 +1207,7 @@ async def pick_up_tip(
"""

spec, _add_tip_to_instrs = self.plan_check_pick_up_tip(
mount, tip_length, presses, increment
mount=mount, presses=presses, increment=increment, tip_length=tip_length
)
self._backend.set_active_current(spec.plunger_currents)
target_absolute = target_position_from_plunger(
Expand All @@ -1200,7 +1218,24 @@ async def pick_up_tip(
home_flagged_axes=False,
)

await self.tip_pickup_moves(mount, spec)
for press in spec.presses:
with self._backend.save_current():
self._backend.set_active_current(press.current)
target_down = target_position_from_relative(
mount, press.relative_down, self._current_position
)
await self._move(target_down, speed=press.speed)
target_up = target_position_from_relative(
mount, press.relative_up, self._current_position
)
await self._move(target_up)
# neighboring tips tend to get stuck in the space between
# the volume chamber and the drop-tip sleeve on p1000.
# This extra shake ensures those tips are removed
for rel_point, speed in spec.shake_off_list:
await self.move_rel(mount, rel_point, speed=speed)

await self.retract(mount, spec.retract_target)
_add_tip_to_instrs()

if prep_after:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -744,28 +744,28 @@ def build_one_shake() -> List[Tuple[top_types.Point, Optional[float]]]:
def plan_check_pick_up_tip(
self,
mount: top_types.Mount,
tip_length: float,
presses: Optional[int],
increment: Optional[float],
tip_length: float = 0,
) -> Tuple[PickUpTipSpec, Callable[[], None]]:
...

@overload
def plan_check_pick_up_tip(
self,
mount: OT3Mount,
tip_length: float,
presses: Optional[int],
increment: Optional[float],
tip_length: float = 0,
) -> Tuple[PickUpTipSpec, Callable[[], None]]:
...

def plan_check_pick_up_tip( # type: ignore[no-untyped-def]
self,
mount,
tip_length,
presses,
increment,
tip_length=0,
):
# Prechecks: ready for pickup tip and press/increment are valid
instrument = self.get_pipette(mount)
Expand Down
13 changes: 11 additions & 2 deletions api/src/opentrons/hardware_control/ot3api.py
Original file line number Diff line number Diff line change
Expand Up @@ -1799,7 +1799,7 @@ async def hold_jaw_width(self, jaw_width_mm: int) -> None:

async def tip_pickup_moves(
self,
mount: OT3Mount,
mount: Union[top_types.Mount, OT3Mount],
presses: Optional[int] = None,
increment: Optional[float] = None,
) -> None:
Expand Down Expand Up @@ -2191,6 +2191,15 @@ async def _tip_motor_action(
)
await self.home_gear_motors()

def cache_tip(
self, mount: Union[top_types.Mount, OT3Mount], tip_length: float
) -> None:
realmount = OT3Mount.from_mount(mount)
instrument = self._pipette_handler.get_pipette(realmount)

instrument.add_tip(tip_length=tip_length)
instrument.set_current_volume(0)

async def pick_up_tip(
self,
mount: Union[top_types.Mount, OT3Mount],
Expand All @@ -2209,7 +2218,7 @@ def add_tip_to_instr() -> None:

await self._move_to_plunger_bottom(realmount, rate=1.0)

await self.tip_pickup_moves(realmount, presses, increment)
await self.tip_pickup_moves(mount, presses, increment)

add_tip_to_instr()

Expand Down
6 changes: 6 additions & 0 deletions api/src/opentrons/hardware_control/protocols/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ class HardwareControlInterface(
def get_robot_type(self) -> Type[OT2RobotType]:
return OT2RobotType

def cache_tip(self, mount: MountArgType, tip_length: float) -> None:
...


class FlexHardwareControlInterface(
ModuleProvider,
Expand Down Expand Up @@ -90,6 +93,9 @@ def motor_status_ok(self, axis: Axis) -> bool:
def encoder_status_ok(self, axis: Axis) -> bool:
...

def cache_tip(self, mount: MountArgType, tip_length: float) -> None:
...


__all__ = [
"HardwareControlAPI",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,14 @@ async def blow_out(
"""
...

async def tip_pickup_moves(
self,
mount: MountArgType,
presses: Optional[int] = None,
increment: Optional[float] = None,
) -> None:
...

async def pick_up_tip(
self,
mount: MountArgType,
Expand Down
2 changes: 1 addition & 1 deletion api/src/opentrons/protocol_engine/errors/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ def __init__(
details: Optional[Dict[str, Any]] = None,
wrapping: Optional[Sequence[EnumeratedError]] = None,
) -> None:
"""Build a PIpetteNotAttachedError."""
"""Build a PipetteNotAttachedError."""
super().__init__(ErrorCodes.UNEXPECTED_TIP_REMOVAL, message, details, wrapping)


Expand Down
10 changes: 5 additions & 5 deletions api/src/opentrons/protocol_engine/execution/tip_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -172,14 +172,14 @@ async def pick_up_tip(
nominal_fallback=nominal_tip_geometry.length,
)

await self._hardware_api.pick_up_tip(
mount=hw_mount,
tip_length=actual_tip_length,
presses=None,
increment=None,
await self._hardware_api.tip_pickup_moves(
mount=hw_mount, presses=None, increment=None
)
await self.verify_tip_presence(pipette_id, TipPresenceStatus.PRESENT)

self._hardware_api.cache_tip(hw_mount, actual_tip_length)
await self._hardware_api.prepare_for_aspirate(hw_mount)

self._hardware_api.set_current_tiprack_diameter(
mount=hw_mount,
tiprack_diameter=nominal_tip_geometry.diameter,
Expand Down
2 changes: 1 addition & 1 deletion api/tests/opentrons/hardware_control/test_instruments.py
Original file line number Diff line number Diff line change
Expand Up @@ -556,7 +556,7 @@ async def test_tip_pickup_moves(sim_and_instr):
spec, _ = hw_api.plan_check_pick_up_tip(
mount=mount, tip_length=40.0, presses=None, increment=None
)
await hw_api.tip_pickup_moves(mount, spec)
await hw_api.tip_pickup_moves(mount=mount)
else:
await hw_api.tip_pickup_moves(mount)

Expand Down
16 changes: 8 additions & 8 deletions api/tests/opentrons/hardware_control/test_moves.py
Original file line number Diff line number Diff line change
Expand Up @@ -289,22 +289,22 @@ async def test_tip_pickup_routine(hardware_api, monkeypatch):
await hardware_api.cache_instruments()
mount = types.Mount.RIGHT

spec, _ = hardware_api.plan_check_pick_up_tip(
mount=mount, tip_length=40.0, presses=None, increment=None
)
await hardware_api.tip_pickup_moves(mount, spec)
presses = 1
await hardware_api.tip_pickup_moves(mount, presses=presses)

tip_motor_routine_num_moves = 2 * len(spec.presses)
# tip pickup moves has an initial move to above the tip, then 2
# moves for each press
tip_motor_routine_num_moves = 2 * presses + 1

# the tip motor routine should only make the immediate 'press' moves happen
assert len(_move.call_args_list) == tip_motor_routine_num_moves
_move.reset_mock()

# pick_up_tip should have the press moves + a plunger move both before and after
await hardware_api.pick_up_tip(
mount=mount, tip_length=40.0, presses=None, increment=None, prep_after=True
mount=mount, tip_length=40.0, presses=1, increment=None, prep_after=True
)
assert len(_move.call_args_list) == tip_motor_routine_num_moves + 2
# pick_up_tip contains an additional retract
assert len(_move.call_args_list) == tip_motor_routine_num_moves + 1


async def test_new_critical_point_applied(hardware_api):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ def test_plan_check_pick_up_tip_with_presses_argument(
)

spec, _add_tip_to_instrs = subject.plan_check_pick_up_tip(
mount, tip_length, presses, increment
mount=mount, tip_length=tip_length, presses=presses, increment=increment
)

assert len(spec.presses) == expected_array_length
Expand Down
72 changes: 70 additions & 2 deletions api/tests/opentrons/protocol_engine/execution/test_tip_handler.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""Pipetting execution handler."""
import pytest
from decoy import Decoy
from mock import AsyncMock, patch

from typing import Dict, ContextManager, Optional
from contextlib import nullcontext as does_not_raise
Expand All @@ -14,6 +15,7 @@
from opentrons.protocol_engine.state import StateView
from opentrons.protocol_engine.types import TipGeometry, TipPresenceStatus
from opentrons.protocol_engine.resources import LabwareDataProvider
from opentrons.protocol_engine.errors.exceptions import TipNotAttachedError
from opentrons_shared_data.errors.exceptions import (
CommandPreconditionViolated,
CommandParameterLimitViolated,
Expand Down Expand Up @@ -76,6 +78,73 @@ async def test_create_tip_handler(
)


@pytest.mark.ot3_only
@pytest.mark.parametrize("tip_state", [TipStateType.PRESENT, TipStateType.ABSENT])
async def test_flex_pick_up_tip_state(
decoy: Decoy,
mock_state_view: StateView,
mock_labware_data_provider: LabwareDataProvider,
tip_rack_definition: LabwareDefinition,
tip_state: TipStateType,
) -> None:
"""Test the protocol engine's pick_up_tip logic."""
from opentrons.hardware_control.ot3api import OT3API

ot3_hardware_api = decoy.mock(cls=OT3API)
decoy.when(ot3_hardware_api.get_robot_type()).then_return(FlexRobotType)

subject = HardwareTipHandler(
state_view=mock_state_view,
hardware_api=ot3_hardware_api,
labware_data_provider=mock_labware_data_provider,
)
decoy.when(subject._state_view.config.robot_type).then_return("OT-3 Standard")
decoy.when(mock_state_view.pipettes.get_mount("pipette-id")).then_return(
MountType.LEFT
)
decoy.when(
mock_state_view.geometry.get_nominal_tip_geometry(
pipette_id="pipette-id",
labware_id="labware-id",
well_name="B2",
)
).then_return(TipGeometry(length=50, diameter=5, volume=300))

decoy.when(
await mock_labware_data_provider.get_calibrated_tip_length(
pipette_serial="pipette-serial",
labware_definition=tip_rack_definition,
nominal_fallback=50,
)
).then_return(42)

with patch.object(
ot3_hardware_api, "cache_tip", AsyncMock(spec=ot3_hardware_api.cache_tip)
) as mock_add_tip:

if tip_state == TipStateType.PRESENT:
await subject.pick_up_tip(
pipette_id="pipette-id",
labware_id="labware-id",
well_name="B2",
)
mock_add_tip.assert_called_once()
else:
decoy.when(
await subject.verify_tip_presence(
pipette_id="pipette-id", expected=TipPresenceStatus.PRESENT
)
).then_raise(TipNotAttachedError())
# if a TipNotAttchedError is caught, we should not add any tip information
with pytest.raises(TipNotAttachedError):
await subject.pick_up_tip(
pipette_id="pipette-id",
labware_id="labware-id",
well_name="B2",
)
mock_add_tip.assert_not_called()


async def test_pick_up_tip(
decoy: Decoy,
mock_state_view: StateView,
Expand Down Expand Up @@ -127,9 +196,8 @@ async def test_pick_up_tip(
assert result == TipGeometry(length=42, diameter=5, volume=300)

decoy.verify(
await mock_hardware_api.pick_up_tip(
await mock_hardware_api.tip_pickup_moves(
mount=Mount.LEFT,
tip_length=42,
presses=None,
increment=None,
),
Expand Down

0 comments on commit cdbc6c1

Please sign in to comment.