Skip to content

Commit 34dd29f

Browse files
authored
Merge pull request #246 from RobotControlStack/juelg/improve-readme
docs: improve readme
2 parents 98b392c + d9d6406 commit 34dd29f

3 files changed

Lines changed: 174 additions & 7 deletions

File tree

README.md

Lines changed: 99 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,101 @@
1-
# Robot Control Stack
2-
3-
**Robot Control Stack (RCS)** is a unified and multilayered robot control interface over a MuJoCo simulation and real world robot currently implemented for the FR3/Panda, xArm7, UR5e and SO101.
4-
5-
![rcs architecture diagram](docs/_static/rcs_architecture_small.svg)
1+
<img src="https://raw.githubusercontent.com/RobotControlStack/robotcontrolstack.github.io/refs/heads/master/static/images/rcs_logo_line.svg" alt="rcs logo" width="100%">
2+
3+
**Robot Control Stack (RCS)** is a flexible Gymnasium wrapper-based robot control interface made for robot learning and specifically Vision-Language-Action (VLA) models.
4+
It unifies MuJoCo simulation and real world robot control with four supported robots: FR3/Panda, xArm7, UR5e and SO101.
5+
It ships with several pre-build apps including data collection via teleoperation and remote model inference via [vlagents](https://github.com/RobotControlStack/vlagents).
6+
7+
8+
<video
9+
src="https://github.com/user-attachments/assets/21ac29af-373b-46aa-8a08-ae0ae8c0e235"
10+
autoplay
11+
muted
12+
loop
13+
playsinline
14+
style="max-width: 100%;">
15+
</video>
16+
17+
## Wrapper-Based Architecture
18+
19+
<img src="docs/_static/rcs_architecture_small.svg" alt="rcs architecture diagram" width="100%">
20+
21+
## Example
22+
Flexibly compose your gym environment to your needs:
23+
```python
24+
from time import sleep
25+
26+
import gymnasium as gym
27+
import numpy as np
28+
from rcs._core.sim import SimConfig
29+
from rcs.camera.sim import SimCameraSet
30+
from rcs.envs.base import (
31+
CameraSetWrapper,
32+
ControlMode,
33+
GripperWrapper,
34+
RelativeActionSpace,
35+
RelativeTo,
36+
RobotEnv,
37+
)
38+
from rcs.envs.sim import GripperWrapperSim, RobotSimWrapper
39+
from rcs.envs.utils import (
40+
default_mujoco_cameraset_cfg,
41+
default_sim_gripper_cfg,
42+
default_sim_robot_cfg,
43+
)
44+
45+
import rcs
46+
from rcs import sim
47+
48+
if __name__ == "__main__":
49+
# default configs
50+
robot_cfg = default_sim_robot_cfg(scene="fr3_empty_world")
51+
gripper_cfg = default_sim_gripper_cfg()
52+
cameras = default_mujoco_cameraset_cfg()
53+
sim_cfg = SimConfig()
54+
sim_cfg.realtime = True
55+
sim_cfg.async_control = True
56+
sim_cfg.frequency = 1 # in Hz (1 sec delay)
57+
58+
simulation = sim.Sim(robot_cfg.mjcf_scene_path, sim_cfg)
59+
ik = rcs.common.Pin(
60+
robot_cfg.kinematic_model_path,
61+
robot_cfg.attachment_site,
62+
urdf=False,
63+
)
64+
65+
# base env
66+
robot = rcs.sim.SimRobot(simulation, ik, robot_cfg)
67+
env: gym.Env = RobotEnv(robot, ControlMode.CARTESIAN_TQuat)
68+
69+
# gripper
70+
gripper = sim.SimGripper(simulation, gripper_cfg)
71+
env = GripperWrapper(env, gripper, binary=True)
72+
73+
env = RobotSimWrapper(env, simulation)
74+
env = GripperWrapperSim(env, gripper)
75+
76+
# camera
77+
camera_set = SimCameraSet(simulation, cameras, physical_units=True, render_on_demand=True)
78+
env = CameraSetWrapper(env, camera_set, include_depth=True)
79+
80+
# relative actions bounded by 10cm translation and 10 degree rotation
81+
env = RelativeActionSpace(env, max_mov=(0.1, np.deg2rad(10)), relative_to=RelativeTo.LAST_STEP)
82+
83+
env.get_wrapper_attr("sim").open_gui()
84+
# wait for gui to open
85+
sleep(1)
86+
env.reset()
87+
88+
# access low level robot api to get current cartesian position
89+
print(env.unwrapped.robot.get_cartesian_position())
90+
91+
for _ in range(10):
92+
# move 1cm in x direction (forward) and close gripper
93+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
94+
obs, reward, terminated, truncated, info = env.step(act)
95+
print(obs)
96+
```
97+
For common environment compositions factory functions such as `rcs.envs.creators.SimEnvCreator` are provided.
98+
This and other example can be found in the [examples](examples/) folder.
699

7100
## Installation
8101

@@ -57,4 +150,4 @@ If you find RCS useful for your academic work, please consider citing it:
57150
}
58151
```
59152

60-
For more scientific info, visit the [paper website](https://robotcontrolstack.github.io/).
153+
For more scientific info, visit the [paper website](https://robotcontrolstack.github.io/).

docs/_static/rcs_architecture_small.svg

Lines changed: 3 additions & 1 deletion
Loading

examples/fr3/fr3_readme.py

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
from time import sleep
2+
3+
import gymnasium as gym
4+
import numpy as np
5+
from rcs._core.sim import SimConfig
6+
from rcs.camera.sim import SimCameraSet
7+
from rcs.envs.base import (
8+
CameraSetWrapper,
9+
ControlMode,
10+
GripperWrapper,
11+
RelativeActionSpace,
12+
RelativeTo,
13+
RobotEnv,
14+
)
15+
from rcs.envs.sim import GripperWrapperSim, RobotSimWrapper
16+
from rcs.envs.utils import (
17+
default_mujoco_cameraset_cfg,
18+
default_sim_gripper_cfg,
19+
default_sim_robot_cfg,
20+
)
21+
22+
import rcs
23+
from rcs import sim
24+
25+
if __name__ == "__main__":
26+
# default configs
27+
robot_cfg = default_sim_robot_cfg(scene="fr3_empty_world")
28+
gripper_cfg = default_sim_gripper_cfg()
29+
cameras = default_mujoco_cameraset_cfg()
30+
sim_cfg = SimConfig()
31+
sim_cfg.realtime = True
32+
sim_cfg.async_control = True
33+
sim_cfg.frequency = 1 # in Hz (1 sec delay)
34+
35+
simulation = sim.Sim(robot_cfg.mjcf_scene_path, sim_cfg)
36+
ik = rcs.common.Pin(
37+
robot_cfg.kinematic_model_path,
38+
robot_cfg.attachment_site,
39+
urdf=False,
40+
)
41+
42+
# base env
43+
robot = rcs.sim.SimRobot(simulation, ik, robot_cfg)
44+
env: gym.Env = RobotEnv(robot, ControlMode.CARTESIAN_TQuat)
45+
46+
# gripper
47+
gripper = sim.SimGripper(simulation, gripper_cfg)
48+
env = GripperWrapper(env, gripper, binary=True)
49+
50+
env = RobotSimWrapper(env, simulation)
51+
env = GripperWrapperSim(env, gripper)
52+
53+
# camera
54+
camera_set = SimCameraSet(simulation, cameras, physical_units=True, render_on_demand=True)
55+
env = CameraSetWrapper(env, camera_set, include_depth=True)
56+
57+
# relative actions bounded by 10cm translation and 10 degree rotation
58+
env = RelativeActionSpace(env, max_mov=(0.1, np.deg2rad(10)), relative_to=RelativeTo.LAST_STEP)
59+
60+
env.get_wrapper_attr("sim").open_gui()
61+
# wait for gui to open
62+
sleep(1)
63+
env.reset()
64+
65+
# access low level robot api to get current cartesian position
66+
print(env.unwrapped.robot.get_cartesian_position())
67+
68+
for _ in range(10):
69+
# move 1cm in x direction (forward) and close gripper
70+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
71+
obs, reward, terminated, truncated, info = env.step(act)
72+
print(obs)

0 commit comments

Comments
 (0)