@@ -139,8 +139,6 @@ def __call__( # type: ignore
139139 gripper_cfg : rcs .sim .SimGripperConfig | None = None ,
140140 random_pos_args : dict | None = None ,
141141 ) -> gym .Env :
142- if random_pos_args is None :
143- random_pos_args = {}
144142 mode = "gripper"
145143 if gripper_cfg is None and hand_cfg is None :
146144 _gripper_cfg = default_sim_gripper_cfg ()
@@ -158,13 +156,13 @@ def __call__( # type: ignore
158156 logger .info ("Using gripper configuration." )
159157
160158 random_env = RandomCubePos
161- if random_pos_args :
159+ if random_pos_args is not None :
162160 # check that all the keys are there
163161 required_keys = ["joint_name" , "init_object_pose" ]
164162 if not all (key in random_pos_args for key in required_keys ):
165163 missing_keys = [key for key in required_keys if key not in random_pos_args ]
166164 logger .warning (f"Missing random position arguments: { missing_keys } ; Defaulting to RandomCubePos" )
167- random_env = partial (RandomObjectPos , ** random_pos_args )
165+ random_env = partial (RandomObjectPos , ** random_pos_args ) # type: ignore
168166
169167 env_rel = SimEnvCreator ()(
170168 control_mode = control_mode ,
@@ -197,7 +195,7 @@ def __call__( # type: ignore
197195 cam_list : list [str ] | None = None ,
198196 ) -> gym .Env :
199197 if cam_list is None :
200- cam_list = [],
198+ cam_list = []
201199 if resolution is None :
202200 resolution = (256 , 256 )
203201 cameras = {
@@ -245,8 +243,8 @@ def __call__( # type: ignore
245243 }
246244 robot_cfg = rcs .sim .SimRobotConfig ()
247245 robot_cfg .tcp_offset = rcs .common .Pose (
248- translation = np .array ([0.0 , 0.0 , 0.15 ]),
249- rotation = np .array ([[0.707 , 0.707 , 0 ], [- 0.707 , 0.707 , 0 ], [0 , 0 , 1 ]]),
246+ translation = np .array ([0.0 , 0.0 , 0.15 ]), # type: ignore
247+ rotation = np .array ([[0.707 , 0.707 , 0 ], [- 0.707 , 0.707 , 0 ], [0 , 0 , 1 ]]), # type: ignore
250248 )
251249 robot_cfg .robot_type = rcs .common .RobotType .FR3
252250 robot_cfg .realtime = False
0 commit comments