@@ -55,49 +55,54 @@ def main():
5555 if "lab" not in rcsss .scenes :
5656 logger .error ("This pip package was not built with the UTN lab models, aborting." )
5757 sys .exit ()
58+ resource_manger : FCI | DummyResourceManager
5859 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
5960 user , pw = load_creds_fr3_desk ()
6061 resource_manger = FCI (Desk (ROBOT_IP , user , pw ), unlock = False , lock_when_done = False )
6162 else :
6263 resource_manger = DummyResourceManager ()
6364
6465 with resource_manger :
66+ robot : rcsss .common .Robot
67+ gripper : rcsss .common .Gripper
6568 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
6669 simulation = sim .Sim (rcsss .scenes ["fr3_empty_world" ])
6770 urdf_path = get_urdf_path (URDF_PATH , allow_none_if_not_found = False )
71+ assert urdf_path is not None
6872 ik = rcsss .common .IK (urdf_path )
6973 robot = rcsss .sim .FR3 (simulation , "0" , ik )
7074 cfg = sim .FR3Config ()
7175 cfg .tcp_offset = rcsss .common .Pose (rcsss .common .FrankaHandTCPOffset ())
7276 cfg .realtime = False
7377 robot .set_parameters (cfg )
7478
75- gripper_cfg = sim .FHConfig ()
76- gripper = sim .FrankaHand (simulation , "0" , gripper_cfg )
79+ gripper_cfg_sim = sim .FHConfig ()
80+ gripper = sim .FrankaHand (simulation , "0" , gripper_cfg_sim )
7781
7882 # add camera to have a rendering gui
7983 cameras = {
8084 "default_free" : SimCameraConfig (identifier = "" , type = int (CameraType .default_free )),
8185 "wrist" : SimCameraConfig (identifier = "eye-in-hand_0" , type = int (CameraType .fixed )),
8286 }
8387 cam_cfg = SimCameraSetConfig (cameras = cameras , resolution_width = 1280 , resolution_height = 720 , frame_rate = 20 )
84- camera_set = SimCameraSet (simulation , cam_cfg ) # noqa: F841
88+ camera_set = SimCameraSet (simulation , cam_cfg ) # noqa: F841
8589 simulation .open_gui ()
8690
8791 else :
8892 urdf_path = get_urdf_path (URDF_PATH , allow_none_if_not_found = False )
93+ assert urdf_path is not None
8994 ik = rcsss .common .IK (urdf_path )
90- robot = rcsss .hw .FR3 (ROBOT_IP , str ( rcsss . scenes [ "lab" ]. parent / "fr3.urdf" ), ik )
95+ robot = rcsss .hw .FR3 (ROBOT_IP , ik )
9196 robot_cfg = FR3Config ()
9297 robot_cfg .tcp_offset = rcsss .common .Pose (rcsss .common .FrankaHandTCPOffset ())
9398 robot_cfg .controller = IKController .robotics_library
9499 robot .set_parameters (robot_cfg )
95100
96- gripper_cfg = rcsss .hw .FHConfig ()
97- gripper_cfg .epsilon_inner = gripper_cfg .epsilon_outer = 0.1
98- gripper_cfg .speed = 0.1
99- gripper_cfg .force = 30
100- gripper = rcsss .hw .FrankaHand (ROBOT_IP , gripper_cfg )
101+ gripper_cfg_hw = rcsss .hw .FHConfig ()
102+ gripper_cfg_hw .epsilon_inner = gripper_cfg_hw .epsilon_outer = 0.1
103+ gripper_cfg_hw .speed = 0.1
104+ gripper_cfg_hw .force = 30
105+ gripper = rcsss .hw .FrankaHand (ROBOT_IP , gripper_cfg_hw )
101106 input ("the robot is going to move, press enter whenever you are ready" )
102107
103108 # move to home position and open gripper
@@ -113,7 +118,7 @@ def main():
113118 )
114119 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
115120 simulation .step_until_convergence ()
116- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
121+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
117122 logger .debug (f"sim converged: { simulation .is_converged ()} " )
118123
119124 # 5cm in y direction
@@ -122,7 +127,7 @@ def main():
122127 )
123128 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
124129 simulation .step_until_convergence ()
125- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
130+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
126131 logger .debug (f"sim converged: { simulation .is_converged ()} " )
127132
128133 # 5cm in z direction
@@ -131,7 +136,7 @@ def main():
131136 )
132137 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
133138 simulation .step_until_convergence ()
134- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
139+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
135140 logger .debug (f"sim converged: { simulation .is_converged ()} " )
136141
137142 # rotate the arm 90 degrees around the inverted y and z axis
@@ -141,7 +146,7 @@ def main():
141146 robot .set_cartesian_position (new_pose )
142147 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
143148 simulation .step_until_convergence ()
144- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
149+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
145150 logger .debug (f"sim converged: { simulation .is_converged ()} " )
146151
147152 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
@@ -155,7 +160,7 @@ def main():
155160 )
156161 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
157162 simulation .step_until_convergence ()
158- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
163+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
159164 logger .debug (f"sim converged: { simulation .is_converged ()} " )
160165
161166 # grasp the object
@@ -170,7 +175,7 @@ def main():
170175 )
171176 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
172177 simulation .step_until_convergence ()
173- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
178+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
174179 logger .debug (f"sim converged: { simulation .is_converged ()} " )
175180
176181 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
0 commit comments