Skip to content

Expose iSWAP per-drive predefined-position readers + rotation drive axis accessors#1015

Merged
BioCam merged 8 commits intoPyLabRobot:mainfrom
BioCam:expose-iswap-request-drives-defined-positions
Apr 28, 2026
Merged

Expose iSWAP per-drive predefined-position readers + rotation drive axis accessors#1015
BioCam merged 8 commits intoPyLabRobot:mainfrom
BioCam:expose-iswap-request-drives-defined-positions

Conversation

@BioCam
Copy link
Copy Markdown
Collaborator

@BioCam BioCam commented Apr 28, 2026

This is a crucial step in the "Tame the iSWAP" project (part 4):
accessing the positional information that the iSWAP uses for its firmware-level positioning.

Summary

Adds 5 new public methods on STARBackend for iSWAP introspection.

Predefined-position table readers (one per drive, all read R0 RA):

  • request_iswap_rotation_drive_predefined_positions()
  • request_iswap_wrist_drive_predefined_positions()
  • request_iswap_gripper_predefined_positions()

Each returns a Dict[str, Union[int, float]] with semantic keys that mirror the existing RotationDriveOrientation / WristDriveOrientation enums:

>>> await star.request_iswap_rotation_drive_predefined_positions()
{'home': 13000, 'left': -29007, 'front': 156, 'right': 29068,
 'parking': 29500, 'extra_1': 29068, 'extra_2': 29068, 'extra_3': 29068,
 'extra_4': 29068, 'link_1_len': 137.8}

>>> await star.request_iswap_wrist_drive_predefined_positions()
{'home': -26577, 'right': -26577, 'straight': -8860, 'left': 9044,
 'reverse': 26858, 'parking': -26577, 'extra_1': -26577, 'extra_2': -26577,
 'extra_3': -26577, 'link_2_len': 137.7}

>>> await star.request_iswap_gripper_predefined_positions()
{'home': 13100, 'fully_open': 24120, 'closed': 12960,
 'plate_type_1': 12780, 'plate_type_2': 13100, ...,
 'plate_type_7': 13100}

...which will be crucial for the next step 👀

Rotation drive single-axis accessors (deck coordinates, mm):

  • iswap_rotation_drive_request_x()
  • iswap_rotation_drive_request_z()

Lets callers grab one axis without paying for a full Coordinate query.
Existing iswap_rotation_drive_request_position() simplified to a 4-line composite using the x / y / z accessors.

Internal reorganization (no API impact)

Pre-existing iSWAP-related methods now grouped into three section headers:

# iSWAP: Rotation Drive (Joint 1)
# iSWAP: Wrist Drive (Joint 2)
# iSWAP: Gripper

Each section opens with the drive's exposed constants:

  • iswap_<drive>_drive_min_increment / _max_increment (encoder bounds)
  • iswap_<drive>_drive_<unit>_per_increment (resolution: deg for rotation/wrist, mm for gripper)

The orientation classifiers (request_iswap_rotation_drive_orientation, request_iswap_wrist_drive_orientation) now reference the exposed resolution constants by name instead of magic-numbering the deg/incr factor.

No breaking changes

All 282 of STARBackend's pre-existing methods preserved.
Diff is purely additive (5 new methods) plus internal reorganization (existing methods moved into per-drive sections without any signature change).

BioCam added 4 commits April 28, 2026 11:10
…dicts

- Keys now match the RotationDriveOrientation / WristDriveOrientation enum names (left/front/right, right/straight/left/reverse) instead of opaque firmware indices (w1/w2/w3, t1..t4)

- Link-length values now in mm (link_1_len, link_2_len), not raw increments
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR extends STARBackend with additional iSWAP introspection APIs to read per-drive predefined-position tables (EEPROM via R0 RA) and to query rotation-drive X/Z axes directly, while reorganizing iSWAP-related methods into per-drive sections.

Changes:

  • Add EEPROM predefined-position table readers for iSWAP rotation drive (W), wrist drive (T), and gripper drive (G).
  • Add rotation-drive single-axis accessors (iswap_rotation_drive_request_x(), iswap_rotation_drive_request_z()) and simplify the composite XYZ accessor.
  • Reorganize iSWAP code into drive-specific sections and expose drive constants (bounds/resolution).

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment thread pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py Outdated
Comment thread pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py Outdated
Comment thread pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py
Comment thread pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py
Comment thread pylabrobot/liquid_handling/backends/hamilton/STAR_backend.py Outdated
@BioCam BioCam merged commit 06d8d62 into PyLabRobot:main Apr 28, 2026
20 of 21 checks passed
@rickwierenga
Copy link
Copy Markdown
Member

ideally this would be named iswap_rotation_drive_request_predefined_positions etc.

@BioCam
Copy link
Copy Markdown
Collaborator Author

BioCam commented Apr 28, 2026

ideally this would be named iswap_rotation_drive_request_predefined_positions etc.

very good point, will update immediately

@BioCam
Copy link
Copy Markdown
Collaborator Author

BioCam commented Apr 28, 2026

implemented in #1017

BioCam added a commit that referenced this pull request Apr 28, 2026
* naming alignment of drive predefined position requests

* update stale docstring refs to renamed link-length accessors

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>

---------

Co-authored-by: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants