1- from pylabrobot .arms .backend import ArmBackend
1+ from pylabrobot .arms .backend import ArmBackend , ElbowOrientation
22from pylabrobot .arms .precise_flex .precise_flex_backend_api import PreciseFlexBackendApi
33
44
@@ -7,6 +7,10 @@ class PreciseFlexBackend(ArmBackend):
77 def __init__ (self , host : str , port : int = 10100 , timeout = 20 ) -> None :
88 super ().__init__ ()
99 self .api = PreciseFlexBackendApi (host = host , port = port , timeout = timeout )
10+ self .profile_index : int = 1
11+ self .location_index : int = 1
12+ self .horizontal_compliance : bool = False
13+ self .horizontal_compliance_torque : int = 0
1014
1115 async def setup (self ):
1216 """Initialize the PreciseFlex backend."""
@@ -22,26 +26,132 @@ async def stop(self):
2226 await self .exit ()
2327 await self .api .stop ()
2428
25- async def get_position (self ):
26- """Get the current position of the robot ."""
27- return await self .api .where_c ( )
29+ async def set_speed (self , speed_percent : float ):
30+ """Set the speed percentage of the arm's movement (0-100) ."""
31+ await self .api .set_profile_speed ( self . profile_index , speed_percent )
2832
29- async def attach (self ):
30- """Attach the robot ."""
31- await self .api .attach ( 1 )
33+ async def get_speed (self ) -> float :
34+ """Get the current speed percentage of the arm's movement ."""
35+ return await self .api .get_profile_speed ( self . profile_index )
3236
33- async def detach (self ):
34- """Detach the robot."""
35- await self .api .attach (0 )
37+ async def open_gripper (self ):
38+ """Open the gripper."""
39+ await self .api .open_gripper ()
40+
41+ async def close_gripper (self ):
42+ """Close the gripper."""
43+ await self .api .close_gripper ()
44+
45+ async def is_gripper_closed (self ) -> bool :
46+ """Check if the gripper is currently closed."""
47+ ret_int = await self .api .is_fully_closed ()
48+ if ret_int == - 1 :
49+ return True
50+ else :
51+ return False
52+
53+ async def halt (self ):
54+ """Stop any ongoing movement of the arm."""
55+ await self .api .halt ()
3656
3757 async def home (self ):
3858 """Homes robot."""
3959 await self .api .home ()
4060
61+ async def move_to_safe (self ):
62+ """Move the arm to a predefined safe position."""
63+ await self .api .move_to_safe ()
64+
65+ async def approach_j (self , joint_position : tuple [float , float , float , float , float , float , float ], approach_height : float ):
66+ """Move the arm to a position above the specified coordinates by a certain distance."""
67+ await self .api .set_location_angles (self .location_index , * list (joint_position ))
68+ await self .api .set_location_z_clearance (self .location_index , approach_height )
69+ await self .api .move_appro (self .location_index , self .profile_index )
70+
71+ async def pick_plate_j (self , joint_position : tuple [float , float , float , float , float , float , float ], approach_height : float ):
72+ """Pick a plate from the specified position."""
73+ await self .api .set_location_angles (self .location_index , * list (joint_position ))
74+ await self .api .set_location_z_clearance (self .location_index , approach_height )
75+ await self .api .pick_plate (self .location_index , self .horizontal_compliance , self .horizontal_compliance_torque )
76+
77+ async def place_plate_j (self , joint_position : tuple [float , float , float , float , float , float , float ], approach_height : float ):
78+ """Place a plate at the specified position."""
79+ await self .api .set_location_angles (self .location_index , * list (joint_position ))
80+ await self .api .set_location_z_clearance (self .location_index , approach_height )
81+ await self .api .place_plate (self .location_index , self .horizontal_compliance , self .horizontal_compliance_torque )
82+
83+ async def move_to_j (self , joint_position : tuple [float , float , float , float , float , float , float ]):
84+ """Move the arm to a specified position in 3D space."""
85+ await self .api .move_j (self .location_index , * list (joint_position ))
86+
87+ async def get_position_j (self ) -> tuple [float , float , float , float , float , float , float ]:
88+ """Get the current position of the arm in 3D space."""
89+ return await self .api .where_j ()
90+
91+ async def approach_c (self , cartesian_position : tuple [float , float , float , float , float , float ], approach_height : float , orientation : ElbowOrientation | None = None ):
92+ """Move the arm to a position above the specified coordinates by a certain distance."""
93+ await self .api .set_location_xyz (self .location_index , * list (cartesian_position ))
94+ await self .api .set_location_z_clearance (self .location_index , approach_height )
95+ orientation_int = self ._convert_orientation_enum_to_int (orientation )
96+ await self .api .set_location_config (self .location_index , orientation_int )
97+ await self .api .move_appro (self .location_index , self .profile_index )
98+
99+ async def pick_plate_c (self , cartesian_position : tuple [float , float , float , float , float , float ], approach_height : float , orientation : ElbowOrientation | None = None ):
100+ """Pick a plate from the specified position."""
101+ await self .api .set_location_xyz (self .location_index , * list (cartesian_position ))
102+ await self .api .set_location_z_clearance (self .location_index , approach_height )
103+ orientation_int = self ._convert_orientation_enum_to_int (orientation )
104+ await self .api .set_location_config (self .location_index , orientation_int )
105+ await self .api .pick_plate (self .location_index , self .horizontal_compliance , self .horizontal_compliance_torque )
106+
107+ async def place_plate_c (self , cartesian_position : tuple [float , float , float , float , float , float ], approach_height : float , orientation : ElbowOrientation | None = None ):
108+ """Place a plate at the specified position."""
109+ await self .api .set_location_xyz (self .location_index , * list (cartesian_position ))
110+ await self .api .set_location_z_clearance (self .location_index , approach_height )
111+ orientation_int = self ._convert_orientation_enum_to_int (orientation )
112+ await self .api .set_location_config (self .location_index , orientation_int )
113+ await self .api .place_plate (self .location_index , self .horizontal_compliance , self .horizontal_compliance_torque )
114+
115+ async def move_to_c (self , cartesian_position : tuple [float , float , float , float , float , float ], orientation : ElbowOrientation | None = None ):
116+ """Move the arm to a specified position in 3D space."""
117+ await self .api .move_c (self .profile_index , * list (cartesian_position ), config = self ._convert_orientation_enum_to_int (orientation ))
118+
119+ async def get_position_c (self ) -> tuple [float , float , float , float , float , float , ElbowOrientation | None ]:
120+ """Get the current position of the arm in 3D space."""
121+ position = await self .api .where_c ()
122+ return (* position [:6 ], self ._convert_orientation_int_to_enum (position [6 ]))
123+
124+
125+ def _convert_orientation_int_to_enum (self , orientation_int : int ) -> ElbowOrientation | None :
126+ match orientation_int :
127+ case 1 :
128+ return ElbowOrientation .LEFT
129+ case 2 :
130+ return ElbowOrientation .RIGHT
131+ case _:
132+ return None
133+
134+ def _convert_orientation_enum_to_int (self , orientation : ElbowOrientation | None ) -> int :
135+ match orientation :
136+ case ElbowOrientation .LEFT :
137+ return 1
138+ case ElbowOrientation .RIGHT :
139+ return 2
140+ case _:
141+ return 0
142+
41143 async def home_all (self ):
42144 """Homes all robots."""
43145 await self .api .home_all ()
44146
147+ async def attach (self ):
148+ """Attach the robot."""
149+ await self .api .attach (1 )
150+
151+ async def detach (self ):
152+ """Detach the robot."""
153+ await self .api .attach (0 )
154+
45155 async def power_on_robot (self ):
46156 """Power on the robot."""
47157 await self .api .set_power (True , self .api .timeout )
@@ -54,10 +164,6 @@ async def set_pc_mode(self):
54164 """Set the controller to PC mode."""
55165 await self .api .set_mode (0 )
56166
57- async def set_verbose_mode (self ):
58- """Set the controller to verbose mode."""
59- await self .api .set_mode (1 )
60-
61167 async def select_robot (self , robot_id : int ) -> None :
62168 """Select the specified robot."""
63169 await self .api .select_robot (robot_id )
@@ -66,28 +172,6 @@ async def version(self) -> str:
66172 """Get the robot's version."""
67173 return await self .api .get_version ()
68174
69- async def open_gripper (self ):
70- """Open the gripper."""
71- await self .api .open_gripper ()
72-
73- async def close_gripper (self ):
74- """Close the gripper."""
75- await self .api .close_gripper ()
76-
77175 async def exit (self ):
78176 """Exit the PreciseFlex backend."""
79177 await self .api .exit ()
80-
81-
82- if __name__ == "__main__" :
83-
84- async def main ():
85- arm = PreciseFlexBackend ("192.168.0.1" )
86- await arm .setup ()
87- position = await arm .get_position ()
88- print (position )
89- await arm .open_gripper ()
90- vals = await arm .get_motion_profile_values (1 )
91- print (vals )
92-
93- asyncio .run (main ())
0 commit comments