@@ -21,7 +21,7 @@ class SimWrapper(gym.Wrapper):
2121 def __init__ (self , env : gym .Env , simulation : sim .Sim ):
2222 super ().__init__ (env )
2323 self .unwrapped : FR3Env
24- assert isinstance (self .unwrapped .robot , sim .FR3 ), "Robot must be a sim.FR3 instance."
24+ assert isinstance (self .unwrapped .robot , sim .SimRobot ), "Robot must be a sim.SimRobot instance."
2525 self .sim = simulation
2626
2727
@@ -32,8 +32,8 @@ def __init__(self, env, simulation: sim.Sim, sim_wrapper: Type[SimWrapper] | Non
3232 env = sim_wrapper (env , simulation )
3333 super ().__init__ (env )
3434 self .unwrapped : FR3Env
35- assert isinstance (self .unwrapped .robot , sim .FR3 ), "Robot must be a sim.FR3 instance."
36- self .sim_robot = cast (sim .FR3 , self .unwrapped .robot )
35+ assert isinstance (self .unwrapped .robot , sim .SimRobot ), "Robot must be a sim.SimRobot instance."
36+ self .sim_robot = cast (sim .SimRobot , self .unwrapped .robot )
3737 self .sim = simulation
3838
3939 def step (self , action : dict [str , Any ]) -> tuple [dict [str , Any ], float , bool , bool , dict ]:
@@ -59,7 +59,7 @@ def reset(
5959
6060
6161class GripperWrapperSim (ActObsInfoWrapper ):
62- def __init__ (self , env , gripper : sim .FrankaHand ):
62+ def __init__ (self , env , gripper : sim .SimGripper ):
6363 super ().__init__ (env )
6464 self ._gripper = gripper
6565
@@ -161,8 +161,8 @@ def env_from_xml_paths(
161161 assert isinstance (env .unwrapped , FR3Env )
162162 simulation = sim .Sim (mjmld )
163163 ik = rcsss .common .IK (urdf , max_duration_ms = 300 )
164- robot = rcsss .sim .FR3 (simulation , id , ik )
165- cfg = sim .FR3Config ()
164+ robot = rcsss .sim .SimRobot (simulation , id , ik )
165+ cfg = sim .SimRobotConfig ()
166166 cfg .realtime = False
167167 if tcp_offset is not None :
168168 cfg .tcp_offset = tcp_offset
@@ -180,8 +180,8 @@ def env_from_xml_paths(
180180 c_env : gym .Env = FR3Env (robot , control_mode )
181181 c_env = FR3Sim (c_env , simulation )
182182 if gripper :
183- gripper_cfg = sim .FHConfig ()
184- fh = sim .FrankaHand (simulation , id , gripper_cfg )
183+ gripper_cfg = sim .SimGripperConfig ()
184+ fh = sim .SimGripper (simulation , id , gripper_cfg )
185185 c_env = GripperWrapper (c_env , fh )
186186 c_env = GripperWrapperSim (c_env , fh )
187187 return cls (
@@ -224,7 +224,7 @@ class PickCubeSuccessWrapper(gym.Wrapper):
224224 def __init__ (self , env ):
225225 super ().__init__ (env )
226226 self .unwrapped : FR3Env
227- assert isinstance (self .unwrapped .robot , sim .FR3 ), "Robot must be a sim.FR3 instance."
227+ assert isinstance (self .unwrapped .robot , sim .SimRobot ), "Robot must be a sim.SimRobot instance."
228228 self .sim = env .get_wrapper_attr ("sim" )
229229
230230 def step (self , action : dict [str , Any ]):
@@ -248,9 +248,11 @@ class CamRobot(gym.Wrapper):
248248 def __init__ (self , env , cam_robot_joints : Vec7Type , scene : str = "lab_simple_pick_up_digit_hand" ):
249249 super ().__init__ (env )
250250 self .unwrapped : FR3Env
251- assert isinstance (self .unwrapped .robot , sim .FR3 ), "Robot must be a sim.FR3 instance."
251+ assert isinstance (self .unwrapped .robot , sim .SimRobot ), "Robot must be a sim.SimRobot instance."
252252 self .sim = env .get_wrapper_attr ("sim" )
253- self .cam_robot = rcsss .sim .FR3 (self .sim , "1" , env .unwrapped .robot .get_ik (), register_convergence_callback = False )
253+ self .cam_robot = rcsss .sim .SimRobot (
254+ self .sim , "1" , env .unwrapped .robot .get_ik (), register_convergence_callback = False
255+ )
254256 self .cam_robot .set_parameters (default_fr3_sim_robot_cfg (scene ))
255257 self .cam_robot_joints = cam_robot_joints
256258
0 commit comments