Skip to content

Commit 9174d76

Browse files
committed
refactor: rename FR3Env to RobotEnv
1 parent e4d354d commit 9174d76

File tree

7 files changed

+28
-28
lines changed

7 files changed

+28
-28
lines changed

python/examples/grasp_demo.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
import mujoco
66
import numpy as np
77
from rcsss._core.common import Pose
8-
from rcsss.envs.base import FR3Env, GripperWrapper
8+
from rcsss.envs.base import GripperWrapper, RobotEnv
99

1010
logger = logging.getLogger(__name__)
1111
logger.setLevel(logging.INFO)
@@ -14,7 +14,7 @@
1414
class PickUpDemo:
1515
def __init__(self, env: gym.Env):
1616
self.env = env
17-
self.unwrapped: FR3Env = cast(FR3Env, self.env.unwrapped)
17+
self.unwrapped: RobotEnv = cast(RobotEnv, self.env.unwrapped)
1818
self.home_pose = self.unwrapped.robot.get_cartesian_position()
1919

2020
def _action(self, pose: Pose, gripper: float) -> dict[str, Any]:

python/examples/grasp_demo_lab.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
import mujoco
66
import numpy as np
77
from rcsss._core.common import Pose
8-
from rcsss.envs.base import FR3Env, GripperWrapper
8+
from rcsss.envs.base import GripperWrapper, RobotEnv
99

1010
logger = logging.getLogger(__name__)
1111
logger.setLevel(logging.INFO)
@@ -14,7 +14,7 @@
1414
class PickUpDemo:
1515
def __init__(self, env: gym.Env):
1616
self.env = env
17-
self.unwrapped: FR3Env = cast(FR3Env, self.env.unwrapped)
17+
self.unwrapped: RobotEnv = cast(RobotEnv, self.env.unwrapped)
1818
self.home_pose = self.unwrapped.robot.get_cartesian_position()
1919

2020
def _action(self, pose: Pose, gripper: float) -> dict[str, Any]:

python/rcsss/envs/base.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -148,8 +148,8 @@ class RobotInstance(Enum):
148148
SIMULATION = auto()
149149

150150

151-
class FR3Env(gym.Env):
152-
"""Joint Gym Environment for Franka Research 3.
151+
class RobotEnv(gym.Env):
152+
"""Joint Gym Environment for a single robot arm.
153153
154154
Top view of on the robot. Robot faces into x direction.
155155
z direction faces upwards. (Right handed coordinate axis)
@@ -274,7 +274,7 @@ def __init__(
274274
max_mov: float | tuple[float, float] | None = None,
275275
):
276276
super().__init__(env)
277-
self.unwrapped: FR3Env
277+
self.unwrapped: RobotEnv
278278
self.action_space: gym.spaces.Dict
279279
self.relative_to = relative_to
280280
if (
@@ -483,7 +483,7 @@ class CameraSetWrapper(ActObsInfoWrapper):
483483

484484
def __init__(self, env, camera_set: BaseCameraSet, include_depth: bool = False):
485485
super().__init__(env)
486-
self.unwrapped: FR3Env
486+
self.unwrapped: RobotEnv
487487
self.camera_set = camera_set
488488
self.include_depth = include_depth
489489

@@ -574,7 +574,7 @@ class GripperWrapper(ActObsInfoWrapper):
574574

575575
def __init__(self, env, gripper: common.Gripper, binary: bool = True):
576576
super().__init__(env)
577-
self.unwrapped: FR3Env
577+
self.unwrapped: RobotEnv
578578
self.observation_space: gym.spaces.Dict
579579
self.observation_space.spaces.update(get_space(GripperDictType).spaces)
580580
self.action_space: gym.spaces.Dict

python/rcsss/envs/creators.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,10 @@
1313
from rcsss.envs.base import (
1414
CameraSetWrapper,
1515
ControlMode,
16-
FR3Env,
1716
GripperWrapper,
1817
RelativeActionSpace,
1918
RelativeTo,
19+
RobotEnv,
2020
)
2121
from rcsss.envs.hw import FR3HW
2222
from rcsss.envs.sim import (
@@ -86,7 +86,7 @@ def __call__( # type: ignore
8686
robot = rcsss.hw.FR3(ip, ik)
8787
robot.set_parameters(robot_cfg)
8888

89-
env: gym.Env = FR3Env(robot, ControlMode.JOINTS if collision_guard is not None else control_mode)
89+
env: gym.Env = RobotEnv(robot, ControlMode.JOINTS if collision_guard is not None else control_mode)
9090

9191
env = FR3HW(env)
9292
if gripper_cfg is not None:
@@ -186,7 +186,7 @@ def __call__( # type: ignore
186186
ik = rcsss.common.IK(urdf_path)
187187
robot = rcsss.sim.SimRobot(simulation, "0", ik)
188188
robot.set_parameters(robot_cfg)
189-
env: gym.Env = FR3Env(robot, control_mode)
189+
env: gym.Env = RobotEnv(robot, control_mode)
190190
env = FR3Sim(env, simulation, sim_wrapper)
191191

192192
if camera_set_cfg is not None:

python/rcsss/envs/hw.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@
33

44
import gymnasium as gym
55
from rcsss import hw
6-
from rcsss.envs.base import FR3Env
6+
from rcsss.envs.base import RobotEnv
77

88
_logger = logging.getLogger(__name__)
99

1010

1111
class FR3HW(gym.Wrapper):
1212
def __init__(self, env):
1313
super().__init__(env)
14-
self.unwrapped: FR3Env
14+
self.unwrapped: RobotEnv
1515
assert isinstance(self.unwrapped.robot, hw.FR3), "Robot must be a hw.FR3 instance."
1616
self.hw_robot = cast(hw.FR3, self.unwrapped.robot)
1717

@@ -22,7 +22,7 @@ def step(self, action: Any) -> tuple[dict[str, Any], SupportsFloat, bool, bool,
2222
_logger.error("FrankaControlException: %s", e)
2323
self.hw_robot.automatic_error_recovery()
2424
# TODO: this does not work if some wrappers are in between
25-
# FR3HW and FR3Env
25+
# FR3HW and RobotEnv
2626
return dict(self.unwrapped.get_obs()), 0, False, True, {}
2727

2828
def reset(

python/rcsss/envs/sim.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
import numpy as np
66
import rcsss
77
from rcsss import sim
8-
from rcsss.envs.base import ControlMode, FR3Env, GripperWrapper
8+
from rcsss.envs.base import ControlMode, GripperWrapper, RobotEnv
99
from rcsss.envs.space_utils import ActObsInfoWrapper, Vec7Type
1010
from rcsss.envs.utils import default_fr3_sim_robot_cfg
1111

@@ -20,7 +20,7 @@ class SimWrapper(gym.Wrapper):
2020

2121
def __init__(self, env: gym.Env, simulation: sim.Sim):
2222
super().__init__(env)
23-
self.unwrapped: FR3Env
23+
self.unwrapped: RobotEnv
2424
assert isinstance(self.unwrapped.robot, sim.SimRobot), "Robot must be a sim.SimRobot instance."
2525
self.sim = simulation
2626

@@ -31,7 +31,7 @@ def __init__(self, env, simulation: sim.Sim, sim_wrapper: Type[SimWrapper] | Non
3131
if sim_wrapper is not None:
3232
env = sim_wrapper(env, simulation)
3333
super().__init__(env)
34-
self.unwrapped: FR3Env
34+
self.unwrapped: RobotEnv
3535
assert isinstance(self.unwrapped.robot, sim.SimRobot), "Robot must be a sim.SimRobot instance."
3636
self.sim_robot = cast(sim.SimRobot, self.unwrapped.robot)
3737
self.sim = simulation
@@ -87,7 +87,7 @@ def __init__(
8787
truncate_on_collision: bool = True,
8888
):
8989
super().__init__(env)
90-
self.unwrapped: FR3Env
90+
self.unwrapped: RobotEnv
9191
self.collision_env = collision_env
9292
self.sim = simulation
9393
self.last_obs: tuple[dict[str, Any], dict[str, Any]] | None = None
@@ -111,7 +111,7 @@ def step(self, action: dict[str, Any]) -> tuple[dict[str, Any], SupportsFloat, b
111111

112112
if self.to_joint_control:
113113
fr3_env = self.collision_env.unwrapped
114-
assert isinstance(fr3_env, FR3Env), "Collision env must be an FR3Env instance."
114+
assert isinstance(fr3_env, RobotEnv), "Collision env must be an RobotEnv instance."
115115
action[self.unwrapped.joints_key] = fr3_env.robot.get_joint_position()
116116

117117
if info["collision"]:
@@ -158,7 +158,7 @@ def env_from_xml_paths(
158158
sim_gui: bool = True,
159159
truncate_on_collision: bool = True,
160160
) -> "CollisionGuard":
161-
assert isinstance(env.unwrapped, FR3Env)
161+
assert isinstance(env.unwrapped, RobotEnv)
162162
simulation = sim.Sim(mjmld)
163163
ik = rcsss.common.IK(urdf, max_duration_ms=300)
164164
robot = rcsss.sim.SimRobot(simulation, id, ik)
@@ -177,7 +177,7 @@ def env_from_xml_paths(
177177
to_joint_control = True
178178
else:
179179
control_mode = env.unwrapped.get_control_mode()
180-
c_env: gym.Env = FR3Env(robot, control_mode)
180+
c_env: gym.Env = RobotEnv(robot, control_mode)
181181
c_env = FR3Sim(c_env, simulation)
182182
if gripper:
183183
gripper_cfg = sim.SimGripperConfig()
@@ -223,7 +223,7 @@ class PickCubeSuccessWrapper(gym.Wrapper):
223223

224224
def __init__(self, env):
225225
super().__init__(env)
226-
self.unwrapped: FR3Env
226+
self.unwrapped: RobotEnv
227227
assert isinstance(self.unwrapped.robot, sim.SimRobot), "Robot must be a sim.SimRobot instance."
228228
self.sim = env.get_wrapper_attr("sim")
229229

@@ -247,7 +247,7 @@ class CamRobot(gym.Wrapper):
247247

248248
def __init__(self, env, cam_robot_joints: Vec7Type, scene: str = "lab_simple_pick_up_digit_hand"):
249249
super().__init__(env)
250-
self.unwrapped: FR3Env
250+
self.unwrapped: RobotEnv
251251
assert isinstance(self.unwrapped.robot, sim.SimRobot), "Robot must be a sim.SimRobot instance."
252252
self.sim = env.get_wrapper_attr("sim")
253253
self.cam_robot = rcsss.sim.SimRobot(

python/tests/test_sim_envs.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,9 @@
55
import rcsss
66
from rcsss.envs.base import (
77
ControlMode,
8-
FR3Env,
98
GripperDictType,
109
JointsDictType,
10+
RobotEnv,
1111
TQuatDictType,
1212
TRPYDictType,
1313
)
@@ -166,7 +166,7 @@ def test_collision_guard_trpy(self, cfg, gripper_cfg):
166166
max_relative_movement=None,
167167
)
168168
obs, _ = env.reset()
169-
unwrapped = cast(FR3Env, env.unwrapped)
169+
unwrapped = cast(RobotEnv, env.unwrapped)
170170
p1 = unwrapped.robot.get_joint_position()
171171
# an obvious below ground collision action
172172
obs["xyzrpy"][0] = 0.4
@@ -286,7 +286,7 @@ def test_collision_guard_tquat(self, cfg, gripper_cfg):
286286
max_relative_movement=None,
287287
)
288288
obs, _ = env.reset()
289-
unwrapped = cast(FR3Env, env.unwrapped)
289+
unwrapped = cast(RobotEnv, env.unwrapped)
290290
p1 = unwrapped.robot.get_joint_position()
291291
# an obvious below ground collision action
292292
obs["tquat"][0] = 0.4
@@ -379,7 +379,7 @@ def test_collision_guard_joints(self, cfg, gripper_cfg):
379379
max_relative_movement=None,
380380
)
381381
env.reset()
382-
unwrapped = cast(FR3Env, env.unwrapped)
382+
unwrapped = cast(RobotEnv, env.unwrapped)
383383
p1 = unwrapped.robot.get_joint_position()
384384
# the below action is a test_case where there is an obvious collision regardless of the gripper action
385385
collision_act = JointsDictType(joints=np.array([0, 1.78, 0, -1.45, 0, 0, 0], dtype=np.float32))

0 commit comments

Comments
 (0)