Skip to content

Commit 2a83a7f

Browse files
committed
refactor: replaced hard coded fr3.urdf with robot.urdf
1 parent c35e817 commit 2a83a7f

File tree

5 files changed

+66
-2
lines changed

5 files changed

+66
-2
lines changed
File renamed without changes.
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
import logging
2+
3+
import numpy as np
4+
from rcs.envs.base import ControlMode, RelativeTo
5+
from rcs.envs.creators import SimEnvCreator
6+
7+
import rcs
8+
from rcs import sim
9+
10+
logger = logging.getLogger(__name__)
11+
logger.setLevel(logging.INFO)
12+
13+
14+
def main():
15+
16+
robot_cfg = sim.SimRobotConfig()
17+
robot_cfg.actuators = ["shoulder_pan", "shoulder_lift", "elbow", "wrist_1", "wrist_2", "wrist_3"]
18+
robot_cfg.joints = [
19+
"shoulder_pan_joint",
20+
"shoulder_lift_joint",
21+
"elbow_joint",
22+
"wrist_1_joint",
23+
"wrist_2_joint",
24+
"wrist_3_joint",
25+
]
26+
robot_cfg.base = "base"
27+
robot_cfg.robot_type = rcs.common.RobotType.UR5e
28+
robot_cfg.attachment_site = "attachment_site"
29+
robot_cfg.arm_collision_geoms = []
30+
env_rel = SimEnvCreator()(
31+
control_mode=ControlMode.CARTESIAN_TQuat,
32+
collision_guard=False,
33+
robot_cfg=robot_cfg,
34+
gripper_cfg=None,
35+
# cameras=default_mujoco_cameraset_cfg(),
36+
max_relative_movement=0.5,
37+
relative_to=RelativeTo.LAST_STEP,
38+
mjcf=rcs.scenes["ur5e_empty_world"]["mjb"],
39+
urdf_path=rcs.scenes["ur5e_empty_world"]["urdf"],
40+
)
41+
env_rel.get_wrapper_attr("sim").open_gui()
42+
env_rel.reset()
43+
44+
45+
for _ in range(10):
46+
for _ in range(10):
47+
# move 1cm in x direction (forward) and close gripper
48+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
49+
obs, reward, terminated, truncated, info = env_rel.step(act)
50+
if truncated or terminated:
51+
logger.info("Truncated or terminated!")
52+
return
53+
for _ in range(10):
54+
# move 1cm in negative x direction (backward) and open gripper
55+
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1}
56+
obs, reward, terminated, truncated, info = env_rel.step(act)
57+
if truncated or terminated:
58+
logger.info("Truncated or terminated!")
59+
return
60+
61+
62+
63+
if __name__ == "__main__":
64+
main()

examples/ur5e_env_joint_control.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ def main():
3535
# cameras=default_mujoco_cameraset_cfg(),
3636
max_relative_movement=np.deg2rad(5),
3737
relative_to=RelativeTo.LAST_STEP,
38-
mjcf=rcs.scenes["ur5e_empty_world"]["mjcf"],
38+
mjcf=rcs.scenes["ur5e_empty_world"]["mjb"],
3939
urdf_path=rcs.scenes["ur5e_empty_world"]["urdf"],
4040
)
4141
env_rel.get_wrapper_attr("sim").open_gui()

python/rcs/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
scenes: dict[str, dict[str, pathlib.Path]] = {
1414
path.stem: {
1515
"mjb": path / "scene.mjb",
16-
"urdf": path / "fr3.urdf",
16+
"urdf": path / "robot.urdf",
1717
}
1818
for path in (pathlib.Path(site.getsitepackages()[0]) / "rcs" / "scenes").glob("*")
1919
}

0 commit comments

Comments
 (0)