Skip to content

Commit 55d3bea

Browse files
committed
STARBackend.iswap_{open,close}_gripper mm units, correct docs
1 parent d294e04 commit 55d3bea

File tree

2 files changed

+42
-27
lines changed

2 files changed

+42
-27
lines changed

docs/user_guide/00_liquid-handling/hamilton-star/iswap-module.md

Lines changed: 26 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,27 @@ The `R0` module allows fine grained control of the iSWAP gripper.
99
You can park the iSWAP using {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.park_iswap`.
1010

1111
```python
12-
await star.park_iswap()
12+
await star_backend.park_iswap()
1313
```
1414

1515
- Opening gripper:
1616

1717
You can open the iSWAP gripper using {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.iswap_open_gripper`. Warning: this will release any object that is gripped. Used for error recovery.
1818

1919
```python
20-
await star.iswap_open_gripper()
20+
# opening all the way
21+
await star_backend.iswap_open_gripper()
22+
```
23+
24+
```python
25+
# opening partially to 90mm
26+
await star_backend.iswap_open_gripper(open_position=90)
27+
```
28+
29+
- Closing gripper: note: this will throw an error if there is no object to grip.
30+
31+
```python
32+
await star_backend.iswap_close_gripper()
2133
```
2234

2335
## Rotations
@@ -39,18 +51,18 @@ Moving the iswap between two positions with the same `grip_direction` while chan
3951
You can also control the wrist (T-drive) and rotation drive (W-drive) individually using {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.rotate_iswap_wrist` and {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.rotate_iswap_rotation_drive` respectively. Make sure you have enough space (you can use {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.move_iswap_y_relative`)
4052

4153
```python
42-
rotation_drive = random.choice([STAR.RotationDriveOrientation.LEFT, STAR.RotationDriveOrientation.RIGHT, STAR.RotationDriveOrientation.FRONT])
43-
wrist_drive = random.choice([STAR.WristOrientation.LEFT, STAR.WristOrientation.RIGHT, STAR.WristOrientation.STRAIGHT, STAR.WristOrientation.REVERSE])
44-
await lh.backend.rotate_iswap_rotation_drive(rotation_drive)
45-
await lh.backend.rotate_iswap_wrist(wrist_drive)
54+
rotation_drive = random.choice([STARBackend.RotationDriveOrientation.LEFT, STARBackend.RotationDriveOrientation.RIGHT, STARBackend.RotationDriveOrientation.FRONT])
55+
wrist_drive = random.choice([STARBackend.WristDriveOrientation.LEFT, STARBackend.WristDriveOrientation.RIGHT, STARBackend.WristDriveOrientation.STRAIGHT, STARBackend.WristDriveOrientation.REVERSE])
56+
await star_backend.rotate_iswap_rotation_drive(rotation_drive)
57+
await star_backend.rotate_iswap_wrist(wrist_drive)
4658
```
4759

4860
## Slow movement
4961

5062
You can make the iswap move more slowly during sensitive operations using {meth}`~pylabrobot.liquid_handling.backends.hamilton.STAR_backend.STARBackend.slow_iswap`. This is useful when you want to avoid splashing or other disturbances.
5163

5264
```python
53-
async with star.slow_iswap():
65+
async with star_backend.slow_iswap():
5466
await lh.move_plate(plate, plt_car[1])
5567
```
5668

@@ -59,23 +71,23 @@ async with star.slow_iswap():
5971
1. For safety, move the other components as far away as possible before teaching. This is easily done using the firmware command `C0FY`, implemented in PLR as `position_components_for_free_iswap_y_range`:
6072

6173
```python
62-
await star.position_components_for_free_iswap_y_range()
74+
await star_backend.position_components_for_free_iswap_y_range()
6375
```
6476

6577
2. Move the iSWAP wrist and rotation drive to the correct orientation as [explained above](#rotations). Repeated: be careful to move the iSWAP to a position where it does not hit any other components. See commands below for how to do this.
6678

6779
3. You can then use the following three commands to move the iSWAP in the X, Y and Z directions. All units are in mm.
6880

6981
```python
70-
await star.move_iswap_x(x)
82+
await star_backend.move_iswap_x(x)
7183
```
7284

7385
```python
74-
await star.move_iswap_y(y)
86+
await star_backend.move_iswap_y(y)
7587
```
7688

7789
```python
78-
await star.move_iswap_z(z)
90+
await star_backend.move_iswap_z(z)
7991
```
8092

8193
4. Note that the x, y and z here refer to the **center** of the iSWAP gripper. This is to make it agnostic to plate size. But in PLR all locations are with respect to LFB (left front bottom) of the plate. To get the LFB after calibrating to the center, subtract the distance from the plate LFB to CCB:
@@ -101,15 +113,15 @@ This will be the location of the plate wrt the parent. You can use this with `pa
101113
You can also move the iSWAP relative to its current position using the following commands. All units are in mm.
102114

103115
```python
104-
await star.move_iswap_x_relative(x)
116+
await star_backend.move_iswap_x_relative(x)
105117
```
106118

107119
```python
108-
await star.move_iswap_y_relative(y)
120+
await star_backend.move_iswap_y_relative(y)
109121
```
110122

111123
```python
112-
await star.move_iswap_z_relative(z)
124+
await star_backend.move_iswap_z_relative(z)
113125
```
114126

115127
This is the center of the iSWAP gripper. See the note above.

pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py

Lines changed: 16 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -7287,45 +7287,48 @@ async def move_iswap_z(self, z_position: float):
72877287
async def open_not_initialized_gripper(self):
72887288
return await self.send_command(module="C0", command="GI")
72897289

7290-
async def iswap_open_gripper(self, open_position: Optional[int] = None):
7290+
async def iswap_open_gripper(self, open_position: Optional[float] = None):
72917291
"""Open gripper
72927292
72937293
Args:
7294-
open_position: Open position [0.1mm] (0.1 mm = 16 increments) The gripper moves to pos + 20.
7294+
open_position: Open position [mm] (0.1 mm = 16 increments) The gripper moves to pos + 20.
72957295
Must be between 0 and 9999. Default 1320 for iSWAP 4.0 (landscape). Default to
72967296
910 for iSWAP 3 (portrait).
72977297
"""
72987298

72997299
if open_position is None:
7300-
open_position = 910 if (await self.get_iswap_version()).startswith("3") else 1320
7300+
open_position = 91.0 if (await self.get_iswap_version()).startswith("3") else 132.0
73017301

7302-
assert 0 <= open_position <= 9999, "open_position must be between 0 and 9999"
7302+
assert 0 <= open_position <= 999.9, "open_position must be between 0 and 999.9"
73037303

7304-
return await self.send_command(module="C0", command="GF", go=f"{open_position:04}")
7304+
return await self.send_command(module="C0", command="GF", go=f"{round(open_position*10):04}")
73057305

73067306
async def iswap_close_gripper(
73077307
self,
73087308
grip_strength: int = 5,
7309-
plate_width: int = 0,
7310-
plate_width_tolerance: int = 0,
7309+
plate_width: float = 0,
7310+
plate_width_tolerance: float = 0,
73117311
):
73127312
"""Close gripper
73137313
7314-
The gripper should be at the position gb+gt+20 before sending this command.
7314+
The gripper should be at the position plate_width+plate_width_tolerance+2.0mm before sending this command.
73157315
73167316
Args:
73177317
grip_strength: Grip strength. 0 = low . 9 = high. Default 5.
7318-
plate_width: Plate width [0.1mm]
7319-
(gb should be > min. Pos. + stop ramp + gt -> gb > 760 + 5 + g )
7320-
plate_width_tolerance: Plate width tolerance [0.1mm]. Must be between 0 and 99. Default 20.
7318+
plate_width: Plate width [mm] (gb should be > min. Pos. + stop ramp + gt -> gb > 760 + 5 + g )
7319+
plate_width_tolerance: Plate width tolerance [mm]. Must be between 0 and 9.9. Default 2.0.
73217320
"""
73227321

7322+
assert 0 <= grip_strength <= 9, "grip_strength must be between 0 and 9"
7323+
assert 0 <= plate_width <= 999.9, "plate_width must be between 0 and 999.9"
7324+
assert 0 <= plate_width_tolerance <= 9.9, "plate_width_tolerance must be between 0 and 9.9"
7325+
73237326
return await self.send_command(
73247327
module="C0",
73257328
command="GC",
73267329
gw=grip_strength,
7327-
gb=plate_width,
7328-
gt=plate_width_tolerance,
7330+
gb=f"{round(plate_width*10):04}",
7331+
gt=f"{round(plate_width_tolerance*10):02}",
73297332
)
73307333

73317334
# -------------- 3.17.2 Stack handling commands CP --------------

0 commit comments

Comments
 (0)