Skip to content

Commit 82067fa

Browse files
committed
refactor: removed lab specific wrappers
1 parent 6f6f863 commit 82067fa

3 files changed

Lines changed: 1 addition & 105 deletions

File tree

python/rcs/__init__.py

Lines changed: 0 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@
77
from rcs import camera, control, envs, hand, sim
88
from rcs._core import __version__, common, hw
99
from rcs.envs.creators import (
10-
FR3LabPickUpSimDigitHandEnvCreator,
11-
FR3SimplePickUpSimDigitHandEnvCreator,
1210
FR3SimplePickUpSimEnvCreator,
1311
RCSFR3DefaultEnvCreator,
1412
RCSFR3EnvCreator,
@@ -28,15 +26,6 @@
2826
entry_point=FR3SimplePickUpSimEnvCreator(),
2927
)
3028

31-
register(
32-
id="rcs/SimplePickUpSimDigitHand-v0",
33-
entry_point=FR3SimplePickUpSimDigitHandEnvCreator(),
34-
)
35-
register(
36-
id="rcs/LabPickUpSimDigitHand-v0",
37-
entry_point=FR3LabPickUpSimDigitHandEnvCreator(),
38-
)
39-
4029
register(
4130
id="rcs/FR3Env-v0",
4231
entry_point=RCSFR3EnvCreator(),

python/rcs/envs/creators.py

Lines changed: 0 additions & 67 deletions
Original file line numberDiff line numberDiff line change
@@ -23,15 +23,13 @@
2323
)
2424
from rcs.envs.hw import FR3HW
2525
from rcs.envs.sim import (
26-
CamRobot,
2726
CollisionGuard,
2827
GripperWrapperSim,
2928
PickCubeSuccessWrapper,
3029
RandomCubePos,
3130
RobotSimWrapper,
3231
SimWrapper,
3332
)
34-
from rcs.envs.space_utils import VecType
3533
from rcs.envs.utils import (
3634
default_fr3_hw_gripper_cfg,
3735
default_fr3_hw_robot_cfg,
@@ -350,68 +348,3 @@ def __call__( # type: ignore
350348
}
351349

352350
return SimTaskEnvCreator()("fr3_simple_pick_up", render_mode, control_mode, delta_actions, cameras)
353-
354-
355-
class FR3SimplePickUpSimDigitHandEnvCreator(EnvCreator):
356-
def __call__( # type: ignore
357-
self,
358-
render_mode: str = "human",
359-
control_mode: ControlMode = ControlMode.CARTESIAN_TRPY,
360-
resolution: tuple[int, int] | None = None,
361-
frame_rate: int = 0,
362-
delta_actions: bool = True,
363-
) -> gym.Env:
364-
if resolution is None:
365-
resolution = (256, 256)
366-
367-
cameras = {
368-
"wrist": SimCameraConfig(
369-
identifier="wrist_0",
370-
type=CameraType.fixed,
371-
resolution_height=resolution[1],
372-
resolution_width=resolution[0],
373-
frame_rate=frame_rate,
374-
)
375-
}
376-
377-
return SimTaskEnvCreator()("fr3_simple_pick_up_digit_hand", render_mode, control_mode, delta_actions, cameras)
378-
379-
380-
class FR3LabPickUpSimDigitHandEnvCreator(EnvCreator):
381-
def __call__( # type: ignore
382-
self,
383-
cam_robot_joints: VecType,
384-
render_mode: str = "human",
385-
control_mode: ControlMode = ControlMode.CARTESIAN_TRPY,
386-
resolution: tuple[int, int] | None = None,
387-
frame_rate: int = 0,
388-
delta_actions: bool = True,
389-
) -> gym.Env:
390-
if resolution is None:
391-
resolution = (256, 256)
392-
393-
cameras = {
394-
"wrist": SimCameraConfig(
395-
identifier="wrist_0",
396-
type=CameraType.fixed,
397-
resolution_height=resolution[1],
398-
resolution_width=resolution[0],
399-
frame_rate=frame_rate,
400-
),
401-
"side": SimCameraConfig(
402-
identifier="wrist_1",
403-
type=CameraType.fixed,
404-
resolution_height=resolution[1],
405-
resolution_width=resolution[0],
406-
frame_rate=frame_rate,
407-
),
408-
}
409-
410-
env_rel = SimTaskEnvCreator()(
411-
"lab_simple_pick_up_digit_hand",
412-
render_mode,
413-
control_mode,
414-
delta_actions,
415-
cameras,
416-
)
417-
return CamRobot(env_rel, cam_robot_joints, "lab_simple_pick_up_digit_hand")

python/rcs/envs/sim.py

Lines changed: 1 addition & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
import rcs
77
from rcs import sim
88
from rcs.envs.base import ControlMode, GripperWrapper, MultiRobotWrapper, RobotEnv
9-
from rcs.envs.space_utils import ActObsInfoWrapper, VecType
9+
from rcs.envs.space_utils import ActObsInfoWrapper
1010
from rcs.envs.utils import default_fr3_sim_robot_cfg
1111

1212
logger = logging.getLogger(__name__)
@@ -313,29 +313,3 @@ def step(self, action: dict[str, Any]):
313313
# normalize
314314
reward /= 5 # type: ignore
315315
return obs, reward, success, truncated, info
316-
317-
318-
class CamRobot(gym.Wrapper):
319-
"""Use this wrapper in lab setups where the second arm is used as a camera holder."""
320-
321-
def __init__(self, env, cam_robot_joints: VecType, scene: str = "lab_simple_pick_up_digit_hand"):
322-
super().__init__(env)
323-
self.unwrapped: RobotEnv
324-
assert isinstance(self.unwrapped.robot, sim.SimRobot), "Robot must be a sim.SimRobot instance."
325-
self.sim = env.get_wrapper_attr("sim")
326-
cfg = default_fr3_sim_robot_cfg(scene, "1")
327-
self.cam_robot = rcs.sim.SimRobot(
328-
self.sim, env.unwrapped.robot.get_ik(), cfg, register_convergence_callback=False
329-
)
330-
self.cam_robot.set_parameters(default_fr3_sim_robot_cfg(scene))
331-
self.cam_robot_joints = cam_robot_joints
332-
333-
def step(self, action: dict):
334-
self.cam_robot.set_joints_hard(self.cam_robot_joints)
335-
obs, reward, done, truncated, info = super().step(action)
336-
return obs, reward, done, truncated, info
337-
338-
def reset(self, *, seed=None, options=None):
339-
re = super().reset(seed=seed, options=options)
340-
self.cam_robot.reset()
341-
return re

0 commit comments

Comments
 (0)