11import logging
22import sys
3- from time import sleep
43
54import numpy as np
65import rcsss
7- from dotenv import dotenv_values
86from rcsss import sim
97from rcsss ._core .hw import FR3Config , IKController
108from rcsss ._core .sim import CameraType
@@ -57,49 +55,54 @@ def main():
5755 if "lab" not in rcsss .scenes :
5856 logger .error ("This pip package was not built with the UTN lab models, aborting." )
5957 sys .exit ()
58+ resource_manger : FCI | DummyResourceManager
6059 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
6160 user , pw = load_creds_fr3_desk ()
6261 resource_manger = FCI (Desk (ROBOT_IP , user , pw ), unlock = False , lock_when_done = False )
6362 else :
6463 resource_manger = DummyResourceManager ()
6564
6665 with resource_manger :
66+ robot : rcsss .common .Robot
67+ gripper : rcsss .common .Gripper
6768 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
6869 simulation = sim .Sim (rcsss .scenes ["fr3_empty_world" ])
6970 urdf_path = get_urdf_path (URDF_PATH , allow_none_if_not_found = False )
71+ assert urdf_path is not None
7072 ik = rcsss .common .IK (urdf_path )
7173 robot = rcsss .sim .FR3 (simulation , "0" , ik )
7274 cfg = sim .FR3Config ()
7375 cfg .tcp_offset = rcsss .common .Pose (rcsss .common .FrankaHandTCPOffset ())
7476 cfg .realtime = False
7577 robot .set_parameters (cfg )
7678
77- gripper_cfg = sim .FHConfig ()
78- gripper = sim .FrankaHand (simulation , "0" , gripper_cfg )
79+ gripper_cfg_sim = sim .FHConfig ()
80+ gripper = sim .FrankaHand (simulation , "0" , gripper_cfg_sim )
7981
8082 # add camera to have a rendering gui
8183 cameras = {
8284 "default_free" : SimCameraConfig (identifier = "" , type = int (CameraType .default_free )),
8385 "wrist" : SimCameraConfig (identifier = "eye-in-hand_0" , type = int (CameraType .fixed )),
8486 }
8587 cam_cfg = SimCameraSetConfig (cameras = cameras , resolution_width = 1280 , resolution_height = 720 , frame_rate = 20 )
86- camera_set = SimCameraSet (simulation , cam_cfg )
88+ camera_set = SimCameraSet (simulation , cam_cfg ) # noqa: F841
8789 simulation .open_gui ()
8890
8991 else :
9092 urdf_path = get_urdf_path (URDF_PATH , allow_none_if_not_found = False )
93+ assert urdf_path is not None
9194 ik = rcsss .common .IK (urdf_path )
92- robot = rcsss .hw .FR3 (ROBOT_IP , str ( rcsss . scenes [ "lab" ]. parent / "fr3.urdf" ), ik )
95+ robot = rcsss .hw .FR3 (ROBOT_IP , ik )
9396 robot_cfg = FR3Config ()
9497 robot_cfg .tcp_offset = rcsss .common .Pose (rcsss .common .FrankaHandTCPOffset ())
9598 robot_cfg .controller = IKController .robotics_library
9699 robot .set_parameters (robot_cfg )
97100
98- gripper_cfg = rcsss .hw .FHConfig ()
99- gripper_cfg .epsilon_inner = gripper_cfg .epsilon_outer = 0.1
100- gripper_cfg .speed = 0.1
101- gripper_cfg .force = 30
102- 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 )
103106 input ("the robot is going to move, press enter whenever you are ready" )
104107
105108 # move to home position and open gripper
@@ -115,7 +118,7 @@ def main():
115118 )
116119 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
117120 simulation .step_until_convergence ()
118- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
121+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
119122 logger .debug (f"sim converged: { simulation .is_converged ()} " )
120123
121124 # 5cm in y direction
@@ -124,7 +127,7 @@ def main():
124127 )
125128 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
126129 simulation .step_until_convergence ()
127- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
130+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
128131 logger .debug (f"sim converged: { simulation .is_converged ()} " )
129132
130133 # 5cm in z direction
@@ -133,7 +136,7 @@ def main():
133136 )
134137 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
135138 simulation .step_until_convergence ()
136- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
139+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
137140 logger .debug (f"sim converged: { simulation .is_converged ()} " )
138141
139142 # rotate the arm 90 degrees around the inverted y and z axis
@@ -143,7 +146,7 @@ def main():
143146 robot .set_cartesian_position (new_pose )
144147 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
145148 simulation .step_until_convergence ()
146- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
149+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
147150 logger .debug (f"sim converged: { simulation .is_converged ()} " )
148151
149152 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
@@ -157,7 +160,7 @@ def main():
157160 )
158161 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
159162 simulation .step_until_convergence ()
160- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
163+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
161164 logger .debug (f"sim converged: { simulation .is_converged ()} " )
162165
163166 # grasp the object
@@ -172,7 +175,7 @@ def main():
172175 )
173176 if ROBOT_INSTANCE == RobotInstance .SIMULATION :
174177 simulation .step_until_convergence ()
175- logger .debug (f"IK success: { robot .get_state ().ik_success } " )
178+ logger .debug (f"IK success: { robot .get_state ().ik_success } " ) # type: ignore
176179 logger .debug (f"sim converged: { simulation .is_converged ()} " )
177180
178181 if ROBOT_INSTANCE == RobotInstance .HARDWARE :
0 commit comments