Skip to content

Commit 1cb4ab2

Browse files
committed
remove TCP, use existing io.socket
1 parent bdf674b commit 1cb4ab2

File tree

5 files changed

+22
-251
lines changed

5 files changed

+22
-251
lines changed

pylabrobot/arms/arm.py

Lines changed: 3 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -57,9 +57,7 @@ async def move_to_safe(self):
5757
return await self.backend.move_to_safe()
5858

5959
async def approach(
60-
self,
61-
position: Union[CartesianCoords, JointCoords],
62-
access: Optional[AccessPattern] = None
60+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
6361
):
6462
"""Move the arm to an approach position (offset from target).
6563
@@ -71,9 +69,7 @@ async def approach(
7169
return await self.backend.approach(position, access)
7270

7371
async def pick_plate(
74-
self,
75-
position: Union[CartesianCoords, JointCoords],
76-
access: Optional[AccessPattern] = None
72+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
7773
):
7874
"""Pick a plate from the specified position.
7975
@@ -85,9 +81,7 @@ async def pick_plate(
8581
return await self.backend.pick_plate(position, access)
8682

8783
async def place_plate(
88-
self,
89-
position: Union[CartesianCoords, JointCoords],
90-
access: Optional[AccessPattern] = None
84+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
9185
):
9286
"""Place a plate at the specified position.
9387

pylabrobot/arms/backend.py

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ class VerticalAccess:
2121
gripper_offset_mm: Additional vertical offset added when holding a plate,
2222
accounts for gripper thickness (default: 10mm)
2323
"""
24+
2425
approach_height_mm: float = 100
2526
clearance_mm: float = 100
2627
gripper_offset_mm: float = 10
@@ -43,6 +44,7 @@ class HorizontalAccess:
4344
gripper_offset_mm: Additional vertical offset added when holding a plate,
4445
accounts for gripper thickness (default: 10mm)
4546
"""
47+
4648
approach_distance_mm: float = 50
4749
clearance_mm: float = 50
4850
lift_height_mm: float = 100
@@ -97,9 +99,7 @@ async def move_to_safe(self):
9799

98100
@abstractmethod
99101
async def approach(
100-
self,
101-
position: Union[CartesianCoords, JointCoords],
102-
access: Optional[AccessPattern] = None
102+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
103103
):
104104
"""Move the arm to an approach position (offset from target).
105105
@@ -112,9 +112,7 @@ async def approach(
112112

113113
@abstractmethod
114114
async def pick_plate(
115-
self,
116-
position: Union[CartesianCoords, JointCoords],
117-
access: Optional[AccessPattern] = None
115+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
118116
):
119117
"""Pick a plate from the specified position.
120118
@@ -127,9 +125,7 @@ async def pick_plate(
127125

128126
@abstractmethod
129127
async def place_plate(
130-
self,
131-
position: Union[CartesianCoords, JointCoords],
132-
access: Optional[AccessPattern] = None
128+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
133129
):
134130
"""Place a plate at the specified position.
135131

pylabrobot/arms/precise_flex/precise_flex_api.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
from typing import Optional
33

44
from pylabrobot.arms.precise_flex.error_codes import ERROR_CODES
5-
from pylabrobot.io.tcp import TCP
5+
from pylabrobot.io.socket import Socket
66

77

88
class PreciseFlexError(Exception):
@@ -31,7 +31,7 @@ def __init__(self, host: str = "192.168.0.1", port: int = 10100, timeout=20) ->
3131
self.host = host
3232
self.port = port
3333
self.timeout = timeout
34-
self.io = TCP(host=self.host, port=self.port)
34+
self.io = Socket(host=self.host, port=self.port)
3535

3636
async def setup(self):
3737
"""Connect to the PreciseFlex backend."""

pylabrobot/arms/precise_flex/precise_flex_backend.py

Lines changed: 12 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -291,9 +291,7 @@ async def version(self) -> str:
291291
return await self.api.get_version()
292292

293293
async def approach(
294-
self,
295-
position: Union[CartesianCoords, JointCoords],
296-
access: Optional[AccessPattern] = None
294+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
297295
):
298296
"""Move the arm to an approach position (offset from target).
299297
@@ -329,10 +327,8 @@ async def approach(
329327
raise ValueError("Position must be of type JointSpace or CartesianSpace.")
330328

331329
async def pick_plate(
332-
self,
333-
position: Union[CartesianCoords, JointCoords],
334-
access: Optional[AccessPattern] = None
335-
):
330+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
331+
):
336332
"""Pick a plate from the specified position.
337333
338334
Args:
@@ -372,9 +368,7 @@ async def pick_plate(
372368
raise ValueError("Position must be of type JointSpace or CartesianSpace.")
373369

374370
async def place_plate(
375-
self,
376-
position: Union[CartesianCoords, JointCoords],
377-
access: Optional[AccessPattern] = None
371+
self, position: Union[CartesianCoords, JointCoords], access: Optional[AccessPattern] = None
378372
):
379373
"""Place a plate at the specified position.
380374
@@ -449,9 +443,7 @@ async def _approach_j(
449443
await self.api.move_appro(self.location_index, self.profile_index)
450444

451445
async def _pick_plate_j(
452-
self,
453-
joint_position: tuple[float, float, float, float, float, float],
454-
access: AccessPattern
446+
self, joint_position: tuple[float, float, float, float, float, float], access: AccessPattern
455447
):
456448
"""Pick a plate from the specified position using joint coordinates."""
457449
await self.api.set_location_angles(self.location_index, *joint_position)
@@ -461,9 +453,7 @@ async def _pick_plate_j(
461453
)
462454

463455
async def _place_plate_j(
464-
self,
465-
joint_position: tuple[float, float, float, float, float, float],
466-
access: AccessPattern
456+
self, joint_position: tuple[float, float, float, float, float, float], access: AccessPattern
467457
):
468458
"""Place a plate at the specified position using joint coordinates."""
469459
await self.api.set_location_angles(self.location_index, *joint_position)
@@ -484,7 +474,7 @@ async def _approach_c(
484474
self,
485475
cartesian_position: tuple[float, float, float, float, float, float],
486476
orientation: int,
487-
access: AccessPattern
477+
access: AccessPattern,
488478
):
489479
"""Move the arm to a position above the specified coordinates.
490480
@@ -501,7 +491,7 @@ async def _pick_plate_c(
501491
self,
502492
cartesian_position: tuple[float, float, float, float, float, float],
503493
orientation: int,
504-
access: AccessPattern
494+
access: AccessPattern,
505495
):
506496
"""Pick a plate from the specified position using Cartesian coordinates."""
507497
await self.api.set_location_xyz(self.location_index, *cartesian_position)
@@ -515,7 +505,7 @@ async def _place_plate_c(
515505
self,
516506
cartesian_position: tuple[float, float, float, float, float, float],
517507
orientation: int,
518-
access: AccessPattern
508+
access: AccessPattern,
519509
):
520510
"""Place a plate at the specified position using Cartesian coordinates."""
521511
await self.api.set_location_xyz(self.location_index, *cartesian_position)
@@ -556,7 +546,7 @@ async def _set_grip_detail(self, access: AccessPattern):
556546
0, # location_type: 0 = normal single location
557547
access.clearance_mm, # z_clearance: vertical retract distance
558548
0, # z_above: not used for vertical access
559-
access.gripper_offset_mm # z_grasp_offset: added when holding plate
549+
access.gripper_offset_mm, # z_grasp_offset: added when holding plate
560550
)
561551
else: # HorizontalAccess
562552
# Horizontal access: access_type=0, z_clearance is horizontal distance
@@ -566,5 +556,5 @@ async def _set_grip_detail(self, access: AccessPattern):
566556
0, # location_type: 0 = normal single location
567557
access.clearance_mm, # z_clearance: horizontal retract distance
568558
access.lift_height_mm, # z_above: vertical lift for horizontal access
569-
access.gripper_offset_mm # z_grasp_offset: added when holding plate
570-
)
559+
access.gripper_offset_mm, # z_grasp_offset: added when holding plate
560+
)

0 commit comments

Comments
 (0)