{ "cells": [ { "cell_type": "markdown", "id": "0fe80c88", "metadata": {}, "source": [ "# Co-Re Grippers\n", "\n", "This tutorial demonstrates how to use the Co-Re grippers on Hamilton STAR liquid handling robots with PyLabRobot.\n", "\n", "The Co-Re grippers mount on pipetting channels and allow for moving labware around the deck." ] }, { "cell_type": "markdown", "id": "55622e0d", "metadata": {}, "source": [ "## Deck setup\n", "\n", "There are two different types of core grippers:\n", "\n", "![Co-Re gripper types](./img/core-grippers/core-gripper-types.jpg)" ] }, { "cell_type": "code", "execution_count": null, "id": "aeb84f69", "metadata": {}, "outputs": [], "source": [ "from pylabrobot.liquid_handling import LiquidHandler, STARBackend\n", "from pylabrobot.liquid_handling.backends.hamilton.STAR_chatterbox import STARChatterboxBackend\n", "from pylabrobot.resources import STARDeck # STARLetDeck\n", "deck = STARDeck(\n", " core_grippers=\"1000uL-at-waste\" # or \"1000uL-5mL-on-waste\"\n", ") # STARLetDeck()\n", "# star_backend = STARChatterboxBackend()\n", "star_backend = STARBackend()\n", "lh = LiquidHandler(backend=star_backend, deck=deck) # STARLetDeck())" ] }, { "cell_type": "markdown", "id": "c158df6a", "metadata": {}, "source": [ "Let's also set up a dummy plate carrier and plate." ] }, { "cell_type": "code", "execution_count": null, "id": "7d024e1b", "metadata": {}, "outputs": [], "source": [ "from pylabrobot.resources import PLT_CAR_L5AC_A00, CellTreat_96_wellplate_350ul_Ub\n", "plate_carrier = PLT_CAR_L5AC_A00(name=\"plate_carrier\")\n", "plate_carrier[0] = plate = CellTreat_96_wellplate_350ul_Ub(name=\"plate\")\n", "deck.assign_child_resource(plate_carrier, rails=14)" ] }, { "cell_type": "markdown", "id": "30168d2b", "metadata": {}, "source": [ "Finally call `setup` to initialize the robot:" ] }, { "cell_type": "code", "execution_count": null, "id": "90b60293", "metadata": {}, "outputs": [], "source": [ "await lh.setup()" ] }, { "cell_type": "markdown", "id": "0a4a6ae0", "metadata": {}, "source": [ "## Moving resources\n", "\n", "There are two apis:\n", "\n", "- `move_resource`: a single call, simple to read. This function calls `pick_up_resource` and `drop_resource` internally.\n", "- `pick_up_resource` and `drop_resource`: two calls, more control over the timing of operations." ] }, { "cell_type": "markdown", "id": "831e8798", "metadata": {}, "source": [ "## `move_resource` api\n", "\n", "This API is the simplest to read:" ] }, { "cell_type": "code", "execution_count": null, "id": "9c6cc552", "metadata": {}, "outputs": [], "source": [ "await lh.move_resource(\n", " plate,\n", " plate_carrier[1],\n", " pickup_distance_from_top=10,\n", "\n", " # Specify to use the core arm.\n", " use_arm=\"core\",\n", "\n", " # use two channels to pick up the core gripper tools. Channels are 0-indexed.\n", " # specify only the front channel. In this case the back channel will be 6.\n", " core_front_channel=7,\n", ")" ] }, { "cell_type": "markdown", "id": "dcd28a93", "metadata": {}, "source": [ "## `pick_up_resource` and `drop_resource` apis\n", "\n", "These APIs give more control over the pick up and drop actions:" ] }, { "cell_type": "code", "execution_count": null, "id": "02b73541", "metadata": {}, "outputs": [], "source": [ "await lh.pick_up_resource(\n", " plate,\n", " pickup_distance_from_top=10,\n", "\n", " # Backend kwargs:\n", "\n", " # Specify to use the core arm.\n", " use_arm=\"core\",\n", "\n", " # use two channels to pick up the core gripper tools. Channels are 0-indexed.\n", " # specify only the front channel. In this case the back channel will be 6.\n", " core_front_channel=7,\n", ")" ] }, { "cell_type": "code", "execution_count": null, "id": "d84fd1e9", "metadata": {}, "outputs": [], "source": [ "await lh.drop_resource(\n", " plate_carrier[1],\n", "\n", " # Backend kwargs:\n", " use_arm=\"core\",\n", " return_core_gripper=True,\n", ")" ] }, { "cell_type": "markdown", "id": "726cd298", "metadata": {}, "source": [ "## Manual control over grippers" ] }, { "cell_type": "code", "execution_count": null, "id": "f89a7b0e", "metadata": {}, "outputs": [], "source": [ "await star_backend.pick_up_core_gripper_tools(front_channel=7)" ] }, { "cell_type": "code", "execution_count": null, "id": "1400f0b4", "metadata": {}, "outputs": [], "source": [ "await star_backend.return_core_gripper_tools()" ] } ], "metadata": { "kernelspec": { "display_name": "env", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.10.15" } }, "nbformat": 4, "nbformat_minor": 5 }