Skip to content

Commit

Permalink
feat(api, shared-data): add pipette plunger backlash compensation (#1…
Browse files Browse the repository at this point in the history
  • Loading branch information
ryanthecoder committed Jun 12, 2023
1 parent 3432bcb commit e17756b
Show file tree
Hide file tree
Showing 68 changed files with 4,194 additions and 71 deletions.
5 changes: 5 additions & 0 deletions api/src/opentrons/hardware_control/instruments/ot3/pipette.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@ def __init__(
self._pipette_type = self._config.pipette_type
self._pipette_version = self._config.version
self._max_channels = self._config.channels
self._backlash_distance = config.backlash_distance

# TODO (lc 12-05-2022) figure out how we can safely deprecate "name" and "model"
self._pipette_name = ot3_pipette_config.PipetteNameType(
Expand Down Expand Up @@ -143,6 +144,10 @@ def config(self) -> PipetteConfigurations:
def channels(self) -> PipetteChannelType:
return self._max_channels

@property
def backlash_distance(self) -> float:
return self._backlash_distance

@property
def tip_overlap(self) -> Dict[str, float]:
return self._tip_overlap
Expand Down
21 changes: 20 additions & 1 deletion api/src/opentrons/hardware_control/ot3api.py
Original file line number Diff line number Diff line change
Expand Up @@ -1417,6 +1417,14 @@ async def _move_to_plunger_bottom(
# save time by using max speed
max_speeds = self.config.motion_settings.default_max_speed
speed = max_speeds[self.gantry_load][OT3AxisKind.P]
if current_pos > target_pos[pip_ax]:
backlash_pos = target_pos.copy()
backlash_pos[pip_ax] -= instrument.backlash_distance
await self._move(
backlash_pos,
speed=(speed * rate),
acquire_lock=acquire_lock,
)
await self._move(
target_pos,
speed=(speed * rate),
Expand Down Expand Up @@ -1451,6 +1459,11 @@ async def aspirate(
)
if not aspirate_spec:
return

checked_mount = OT3Mount.from_mount(mount)
instrument = self._pipette_handler.get_pipette(checked_mount)
pip_ax = OT3Axis.of_main_tool_actuator(mount)

target_pos = target_position_from_plunger(
realmount,
aspirate_spec.plunger_distance,
Expand All @@ -1461,7 +1474,13 @@ async def aspirate(
await self._backend.set_active_current(
{OT3Axis.from_axis(aspirate_spec.axis): aspirate_spec.current}
)

backlash_pos = target_pos.copy()
backlash_pos[pip_ax] -= instrument.backlash_distance
await self._move(
backlash_pos,
speed=aspirate_spec.speed,
home_flagged_axes=False,
)
await self._move(
target_pos,
speed=aspirate_spec.speed,
Expand Down
11 changes: 10 additions & 1 deletion api/tests/opentrons/hardware_control/test_ot3_api.py
Original file line number Diff line number Diff line change
Expand Up @@ -1150,6 +1150,8 @@ async def test_move_to_plunger_bottom(
await ot3_hardware.add_tip(mount, 100)
mock_move.reset_mock()
await ot3_hardware.prepare_for_aspirate(mount)
# make sure when plunger is going down that only one move is called,
# and there's no backlash move queued
mock_move.assert_called_once_with(
target_pos, speed=expected_speed_moving_down, acquire_lock=True
)
Expand All @@ -1161,7 +1163,14 @@ async def test_move_to_plunger_bottom(
ot3_hardware._current_position[pip_ax] = target_pos[pip_ax] + 1
mock_move.reset_mock()
await ot3_hardware.prepare_for_aspirate(mount)
mock_move.assert_called_once_with(
# make sure we've done the backlash compensation
backlash_pos = target_pos.copy()
backlash_pos[pip_ax] -= pipette.backlash_distance
mock_move.assert_any_call(
backlash_pos, speed=expected_speed_moving_up, acquire_lock=True
)
# make sure the final move is to our target position
mock_move.assert_called_with(
target_pos, speed=expected_speed_moving_up, acquire_lock=True
)

Expand Down
4 changes: 4 additions & 0 deletions hardware-testing/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,12 @@ wheel: $(wheel_file)

.PHONY: test
test:
$(MAKE) apply-patches-gravimetric
$(pytest) $(tests) $(test_opts)

.PHONY: test-cov
test-cov:
$(MAKE) apply-patches-gravimetric
$(pytest) $(tests) $(test_opts) $(cov_opts)

.PHONY: test-photometric
Expand Down Expand Up @@ -121,9 +123,11 @@ test-integration: test-production-qc test-examples test-scripts test-gravimetric

.PHONY: lint
lint:
$(MAKE) apply-patches-gravimetric
$(python) -m mypy hardware_testing tests
$(python) -m black --check hardware_testing tests setup.py
$(python) -m flake8 hardware_testing tests setup.py
$(MAKE) remove-patches-gravimetric

.PHONY: format
format:
Expand Down
9 changes: 9 additions & 0 deletions hardware-testing/hardware_testing/gravimetric/__main__.py
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,11 @@ def run_pm(
is_simulating=args.simulate,
)
if args.photometric:
_ctx = helpers.get_api_context(
_protocol.requirements["apiLevel"], # type: ignore[attr-defined]
is_simulating=args.simulate,
deck_version="2",
)
run_pm(
_ctx,
args.pipette,
Expand All @@ -181,6 +186,10 @@ def run_pm(
args.touch_tip,
)
else:
_ctx = helpers.get_api_context(
_protocol.requirements["apiLevel"], # type: ignore[attr-defined]
is_simulating=args.simulate,
)
run(
_ctx,
args.pipette,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -339,7 +339,8 @@ def _no_op() -> None:
added_blow_out=(i + 1) == num_dispenses,
)
if cfg.touch_tip:
pipette.touch_tip(v_offset=-2.0)
ui.get_user_ready("ready")
pipette.touch_tip(speed=30)
pipette.move_to(location=dest["A1"].top().move(Point(0, 0, 133)))
pipette.move_to(location=dest["A1"].top().move(Point(0, 107, 133)))
ui.get_user_ready("Cover and replace the photoplate in slot 3")
Expand Down
4 changes: 3 additions & 1 deletion hardware-testing/hardware_testing/gravimetric/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ def get_api_context(
pipette_right: Optional[str] = None,
gripper: Optional[str] = None,
extra_labware: Optional[Dict[str, LabwareDefinition]] = None,
deck_version: str = guess_deck_type_from_global_config(),
) -> protocol_api.ProtocolContext:
"""Get api context."""

Expand All @@ -68,8 +69,9 @@ async def _thread_manager_build_hw_api(
return protocol_api.create_protocol_context(
api_version=APIVersion.from_string(api_level),
hardware_api=ThreadManager(_thread_manager_build_hw_api), # type: ignore[arg-type]
deck_type=guess_deck_type_from_global_config(),
deck_type="ot3_standard",
extra_labware=extra_labware,
deck_version=2,
)


Expand Down
84 changes: 77 additions & 7 deletions hardware-testing/hardware_testing/gravimetric/overrides/api.patch
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
diff --git a/api/src/opentrons/config/defaults_ot3.py b/api/src/opentrons/config/defaults_ot3.py
index 89696c5b2a..63fdb32bdc 100644
index 89696c5b2a..4c2d6184b8 100644
--- a/api/src/opentrons/config/defaults_ot3.py
+++ b/api/src/opentrons/config/defaults_ot3.py
@@ -83,7 +83,7 @@ DEFAULT_MAX_SPEEDS: Final[ByGantryLoad[Dict[OT3AxisKind, float]]] = ByGantryLoad
OT3AxisKind.X: 500,
OT3AxisKind.Y: 375,
OT3AxisKind.Z: 35,
- OT3AxisKind.P: 5,
+ OT3AxisKind.P: 13,
+ OT3AxisKind.P: 20,
OT3AxisKind.Z_G: 50,
OT3AxisKind.Q: 5.5,
},
Expand All @@ -20,7 +20,8 @@ index 89696c5b2a..63fdb32bdc 100644
+ OT3AxisKind.X: 500,
+ OT3AxisKind.Y: 500,
OT3AxisKind.Z: 120,
OT3AxisKind.P: 30,
- OT3AxisKind.P: 30,
+ OT3AxisKind.P: 1000,
OT3AxisKind.Z_G: 150,
OT3AxisKind.Q: 10,
},
Expand All @@ -40,15 +41,26 @@ index 89696c5b2a..63fdb32bdc 100644
OT3AxisKind.X: 10,
OT3AxisKind.Y: 10,
- OT3AxisKind.Z: 5,
+ OT3AxisKind.Z: 20,
+ OT3AxisKind.Z: 15,
OT3AxisKind.P: 5,
OT3AxisKind.Z_G: 10,
OT3AxisKind.Q: 5,
@@ -176,8 +176,8 @@ DEFAULT_RUN_CURRENT: Final[ByGantryLoad[Dict[OT3AxisKind, float]]] = ByGantryLoa
high_throughput={
OT3AxisKind.X: 1.4,
OT3AxisKind.Y: 1.4,
- OT3AxisKind.Z: 1.4,
- OT3AxisKind.P: 2.2,
+ OT3AxisKind.Z: 1.5,
+ OT3AxisKind.P: 0.8,
OT3AxisKind.Z_G: 0.67,
OT3AxisKind.Q: 1.5,
},
diff --git a/api/src/opentrons/hardware_control/instruments/ot3/pipette.py b/api/src/opentrons/hardware_control/instruments/ot3/pipette.py
index 5f96add2a4..047dc58add 100644
index 3610fc8857..6b4db5dfe5 100644
--- a/api/src/opentrons/hardware_control/instruments/ot3/pipette.py
+++ b/api/src/opentrons/hardware_control/instruments/ot3/pipette.py
@@ -422,11 +422,11 @@ class Pipette(AbstractInstrument[PipetteConfigurations]):
@@ -427,11 +427,11 @@ class Pipette(AbstractInstrument[PipetteConfigurations]):

def set_current_volume(self, new_volume: float) -> None:
assert new_volume >= 0
Expand All @@ -62,7 +74,7 @@ index 5f96add2a4..047dc58add 100644
self._current_volume += volume_incr

def remove_current_volume(self, volume_incr: float) -> None:
@@ -434,7 +434,8 @@ class Pipette(AbstractInstrument[PipetteConfigurations]):
@@ -439,7 +439,8 @@ class Pipette(AbstractInstrument[PipetteConfigurations]):
self._current_volume -= volume_incr

def ok_to_add_volume(self, volume_incr: float) -> bool:
Expand All @@ -72,3 +84,61 @@ index 5f96add2a4..047dc58add 100644

def add_tip(self, tip_length: float) -> None:
"""
diff --git a/api/src/opentrons/protocol_api/core/legacy/deck.py b/api/src/opentrons/protocol_api/core/legacy/deck.py
index 54bca33742..e6b49e47fe 100644
--- a/api/src/opentrons/protocol_api/core/legacy/deck.py
+++ b/api/src/opentrons/protocol_api/core/legacy/deck.py
@@ -47,11 +47,11 @@ class DeckItem(Protocol):
class Deck(UserDict): # type: ignore[type-arg]
data: Dict[int, Optional[DeckItem]]

- def __init__(self, deck_type: str) -> None:
+ def __init__(
+ self, deck_type: str, version: int = DEFAULT_DECK_DEFINITION_VERSION
+ ) -> None:
super().__init__()
- self._definition = load_deck(
- name=deck_type, version=DEFAULT_DECK_DEFINITION_VERSION
- )
+ self._definition = load_deck(name=deck_type, version=version)
self._positions = {}
for slot in self._definition["locations"]["orderedSlots"]:
self.data[int(slot["id"])] = None
diff --git a/api/src/opentrons/protocol_api/create_protocol_context.py b/api/src/opentrons/protocol_api/create_protocol_context.py
index f2d8e492ec..dd4fd9102e 100644
--- a/api/src/opentrons/protocol_api/create_protocol_context.py
+++ b/api/src/opentrons/protocol_api/create_protocol_context.py
@@ -22,6 +22,7 @@ from .deck import Deck

from .core.common import ProtocolCore as AbstractProtocolCore
from .core.legacy.deck import Deck as LegacyDeck
+from opentrons_shared_data.deck import DEFAULT_DECK_DEFINITION_VERSION
from .core.legacy.legacy_protocol_core import LegacyProtocolCore
from .core.legacy.labware_offset_provider import (
AbstractLabwareOffsetProvider,
@@ -52,6 +53,7 @@ def create_protocol_context(
extra_labware: Optional[Dict[str, LabwareDefinition]] = None,
bundled_labware: Optional[Dict[str, LabwareDefinition]] = None,
bundled_data: Optional[Dict[str, bytes]] = None,
+ deck_version: int = DEFAULT_DECK_DEFINITION_VERSION,
) -> ProtocolContext:
"""Create a ProtocolContext for use in a Python protocol.

@@ -121,7 +123,7 @@ def create_protocol_context(

# TODO(mc, 2022-8-22): remove `disable_fast_protocol_upload`
elif use_simulating_core and not feature_flags.disable_fast_protocol_upload():
- legacy_deck = LegacyDeck(deck_type=deck_type)
+ legacy_deck = LegacyDeck(deck_type=deck_type, version=deck_version)
core = LegacyProtocolCoreSimulator(
sync_hardware=sync_hardware,
labware_offset_provider=labware_offset_provider,
@@ -133,7 +135,7 @@ def create_protocol_context(
)

else:
- legacy_deck = LegacyDeck(deck_type=deck_type)
+ legacy_deck = LegacyDeck(deck_type=deck_type, version=deck_version)
core = LegacyProtocolCore(
sync_hardware=sync_hardware,
labware_offset_provider=labware_offset_provider,
Loading

0 comments on commit e17756b

Please sign in to comment.