Skip to content

Commit b65a950

Browse files
authored
Merge pull request #192 from utn-mi/so101-support-clean
Add support for SO101 Robot
2 parents 566a674 + b759e8d commit b65a950

15 files changed

Lines changed: 431 additions & 39 deletions

File tree

pyproject.toml

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,13 +54,18 @@ classifiers = [
5454
# "mypy==1.4.1",
5555
# ]
5656

57+
[project.optional-dependencies]
58+
so101 = [
59+
"lerobot @ git+https://github.com/huggingface/lerobot.git",
60+
]
61+
5762

5863
[tool.scikit-build]
5964
build.verbose = true
6065
build.targets = ["_core", "scenes"]
6166
logging.level = "INFO"
6267
build-dir = "build"
63-
wheel.packages = ["python/rcs"]
68+
wheel.packages = ["python/rcs", "python/rcs_so101"]
6469
install.components = ["python_package"]
6570

6671
[tool.ruff]

python/rcs/_core/common.pyi

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@ __all__ = [
3030
"RobotState",
3131
"RobotType",
3232
"SIMULATION",
33+
"SO101",
3334
"UR5e",
3435
"robots_meta_config",
3536
]
@@ -62,6 +63,7 @@ class GripperState:
6263

6364
class IK:
6465
def __init__(self, urdf_path: str, max_duration_ms: int = 300) -> None: ...
66+
def forward(self, q0: numpy.ndarray[M, numpy.dtype[numpy.float64]], tcp_offset: Pose = ...) -> Pose: ...
6567
def ik(
6668
self, pose: Pose, q0: numpy.ndarray[M, numpy.dtype[numpy.float64]], tcp_offset: Pose = ...
6769
) -> numpy.ndarray[M, numpy.dtype[numpy.float64]] | None: ...
@@ -158,6 +160,7 @@ class Robot:
158160
class RobotConfig:
159161
robot_platform: RobotPlatform
160162
robot_type: RobotType
163+
def __init__(self) -> None: ...
161164

162165
class RobotMetaConfig:
163166
@property
@@ -206,13 +209,16 @@ class RobotType:
206209
FR3
207210
208211
UR5e
212+
213+
SO101
209214
"""
210215

211216
FR3: typing.ClassVar[RobotType] # value = <RobotType.FR3: 0>
217+
SO101: typing.ClassVar[RobotType] # value = <RobotType.SO101: 2>
212218
UR5e: typing.ClassVar[RobotType] # value = <RobotType.UR5e: 1>
213219
__members__: typing.ClassVar[
214220
dict[str, RobotType]
215-
] # value = {'FR3': <RobotType.FR3: 0>, 'UR5e': <RobotType.UR5e: 1>}
221+
] # value = {'FR3': <RobotType.FR3: 0>, 'UR5e': <RobotType.UR5e: 1>, 'SO101': <RobotType.SO101: 2>}
216222
def __eq__(self, other: typing.Any) -> bool: ...
217223
def __getstate__(self) -> int: ...
218224
def __hash__(self) -> int: ...
@@ -238,4 +244,5 @@ def robots_meta_config(robot_type: RobotType) -> RobotMetaConfig: ...
238244
FR3: RobotType # value = <RobotType.FR3: 0>
239245
HARDWARE: RobotPlatform # value = <RobotPlatform.HARDWARE: 1>
240246
SIMULATION: RobotPlatform # value = <RobotPlatform.SIMULATION: 0>
247+
SO101: RobotType # value = <RobotType.SO101: 2>
241248
UR5e: RobotType # value = <RobotType.UR5e: 1>

python/rcs/_core/sim.pyi

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -116,8 +116,11 @@ class SimGripperConfig(rcs._core.common.GripperConfig):
116116
epsilon_inner: float
117117
epsilon_outer: float
118118
ignored_collision_geoms: list[str]
119-
joint1: str
120-
joint2: str
119+
joint: str
120+
max_actuator_width: float
121+
max_joint_width: float
122+
min_actuator_width: float
123+
min_joint_width: float
121124
seconds_between_callbacks: float
122125
def __init__(self) -> None: ...
123126
def add_id(self, id: str) -> None: ...
@@ -132,8 +135,6 @@ class SimGripperState(rcs._core.common.GripperState):
132135
def last_commanded_width(self) -> float: ...
133136
@property
134137
def last_width(self) -> float: ...
135-
@property
136-
def max_unnormalized_width(self) -> float: ...
137138

138139
class SimRobot(rcs._core.common.Robot):
139140
def __init__(

python/rcs/sim/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
from rcs._core.sim import (
2+
SimCameraConfig,
23
SimGripper,
34
SimGripperConfig,
45
SimGripperState,
@@ -17,4 +18,5 @@
1718
"SimGripperConfig",
1819
"SimGripperState",
1920
"gui_loop",
21+
"SimCameraConfig",
2022
]

python/rcs_so101/__init__.py

Whitespace-only changes.

python/rcs_so101/creators.py

Lines changed: 150 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,150 @@
1+
import logging
2+
from os import PathLike
3+
from pathlib import Path
4+
from typing import Type
5+
6+
import gymnasium as gym
7+
import rcs
8+
from gymnasium.envs.registration import EnvCreator
9+
from lerobot.common.robots import make_robot_from_config
10+
from lerobot.common.robots.so101_follower.config_so101_follower import (
11+
SO101FollowerConfig,
12+
)
13+
from lerobot.common.teleoperators.so101_leader.config_so101_leader import (
14+
SO101LeaderConfig,
15+
)
16+
from lerobot.common.teleoperators.so101_leader.so101_leader import SO101Leader
17+
from lerobot.common.teleoperators.utils import make_teleoperator_from_config
18+
from rcs import common, sim
19+
from rcs.camera.hw import HardwareCameraSet
20+
from rcs.camera.sim import SimCameraSet
21+
from rcs.envs.base import (
22+
CameraSetWrapper,
23+
ControlMode,
24+
GripperWrapper,
25+
RelativeActionSpace,
26+
RelativeTo,
27+
RobotEnv,
28+
)
29+
from rcs.envs.creators import RCSHardwareEnvCreator
30+
from rcs.envs.sim import CollisionGuard, GripperWrapperSim, RobotSimWrapper, SimWrapper
31+
from rcs.sim import SimCameraConfig, SimGripperConfig, SimRobotConfig
32+
from rcs_so101.hw import SO101, S0101Gripper
33+
34+
logger = logging.getLogger(__name__)
35+
logger.setLevel(logging.INFO)
36+
37+
38+
class RCSSO101EnvCreator(RCSHardwareEnvCreator):
39+
def __call__( # type: ignore
40+
self,
41+
id: str,
42+
port: str,
43+
urdf_path: str,
44+
calibration_dir: PathLike | str | None = None,
45+
camera_set: HardwareCameraSet | None = None,
46+
max_relative_movement: float | tuple[float, float] | None = None,
47+
relative_to: RelativeTo = RelativeTo.LAST_STEP,
48+
) -> gym.Env:
49+
if isinstance(calibration_dir, str):
50+
calibration_dir = Path(calibration_dir)
51+
cfg = SO101FollowerConfig(id=id, calibration_dir=calibration_dir, port=port)
52+
hf_robot = make_robot_from_config(cfg)
53+
robot = SO101(hf_robot, urdf_path=urdf_path)
54+
env: gym.Env = RobotEnv(robot, ControlMode.JOINTS)
55+
# env = FR3HW(env)
56+
57+
gripper = S0101Gripper(hf_robot)
58+
env = GripperWrapper(env, gripper, binary=False)
59+
60+
if camera_set is not None:
61+
camera_set.start()
62+
camera_set.wait_for_frames()
63+
logger.info("CameraSet started")
64+
env = CameraSetWrapper(env, camera_set)
65+
66+
if max_relative_movement is not None:
67+
env = RelativeActionSpace(env, max_mov=max_relative_movement, relative_to=relative_to)
68+
69+
return env
70+
71+
@staticmethod
72+
def teleoperator(
73+
id: str,
74+
port: str,
75+
calibration_dir: PathLike | str | None = None,
76+
) -> SO101Leader:
77+
if isinstance(calibration_dir, str):
78+
calibration_dir = Path(calibration_dir)
79+
cfg = SO101LeaderConfig(id=id, calibration_dir=calibration_dir, port=port)
80+
teleop = make_teleoperator_from_config(cfg)
81+
teleop.connect()
82+
return teleop
83+
84+
85+
class SO101SimEnvCreator(EnvCreator):
86+
def __call__( # type: ignore
87+
self,
88+
control_mode: ControlMode,
89+
robot_cfg: SimRobotConfig,
90+
urdf_path: str,
91+
mjcf: str,
92+
collision_guard: bool = False,
93+
gripper_cfg: SimGripperConfig | None = None,
94+
cameras: dict[str, SimCameraConfig] | None = None,
95+
max_relative_movement: float | tuple[float, float] | None = None,
96+
relative_to: RelativeTo = RelativeTo.LAST_STEP,
97+
sim_wrapper: Type[SimWrapper] | None = None,
98+
) -> gym.Env:
99+
"""
100+
Creates a simulation environment for the FR3 robot.
101+
Args:
102+
control_mode (ControlMode): Control mode for the robot.
103+
robot_cfg (rcs.sim.SimRobotConfig): Configuration for the FR3 robot.
104+
collision_guard (bool): Whether to use collision guarding. If True, the same mjcf scene is used for collision guarding.
105+
gripper_cfg (rcs.sim.SimGripperConfig | None): Configuration for the gripper. If None, no gripper is used.
106+
camera_set_cfg (SimCameraSetConfig | None): Configuration for the camera set. If None, no cameras are used.
107+
max_relative_movement (float | tuple[float, float] | None): Maximum allowed movement. If float, it restricts
108+
translational movement in meters. If tuple, it restricts both translational (in meters) and rotational
109+
(in radians) movements. If None, no restriction is applied.
110+
relative_to (RelativeTo): Specifies whether the movement is relative to a configured origin or the last step.
111+
urdf_path (str | PathLike | None): Path to the URDF file. If None, the URDF file is automatically deduced
112+
which requires a UTN compatible lab scene to be present.
113+
mjcf (str | PathLike): Path to the Mujoco scene XML file. Defaults to "fr3_empty_world".
114+
sim_wrapper (Type[SimWrapper] | None): Wrapper to be applied before the simulation wrapper. This is useful
115+
for reset management e.g. resetting objects in the scene with correct observations. Defaults to None.
116+
Returns:
117+
gym.Env: The configured simulation environment for the FR3 robot.
118+
"""
119+
simulation = sim.Sim(mjcf)
120+
121+
ik = rcs.common.IK(str(urdf_path))
122+
robot = rcs.sim.SimRobot(simulation, ik, robot_cfg)
123+
env: gym.Env = RobotEnv(robot, control_mode)
124+
env = RobotSimWrapper(env, simulation, sim_wrapper)
125+
126+
if cameras is not None:
127+
camera_set = SimCameraSet(simulation, cameras, physical_units=True, render_on_demand=True)
128+
env = CameraSetWrapper(env, camera_set, include_depth=True)
129+
130+
if gripper_cfg is not None and isinstance(gripper_cfg, SimGripperConfig):
131+
gripper = sim.SimGripper(simulation, gripper_cfg)
132+
env = GripperWrapper(env, gripper, binary=False)
133+
env = GripperWrapperSim(env, gripper)
134+
135+
if collision_guard:
136+
env = CollisionGuard.env_from_xml_paths(
137+
env,
138+
str(rcs.scenes.get(str(mjcf), mjcf)),
139+
str(urdf_path),
140+
gripper=gripper_cfg is not None,
141+
check_home_collision=False,
142+
control_mode=control_mode,
143+
tcp_offset=rcs.common.Pose(common.FrankaHandTCPOffset()),
144+
sim_gui=True,
145+
truncate_on_collision=True,
146+
)
147+
if max_relative_movement is not None:
148+
env = RelativeActionSpace(env, max_mov=max_relative_movement, relative_to=relative_to)
149+
150+
return env
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
import logging
2+
from time import sleep
3+
4+
import rcs
5+
from rcs import sim
6+
from rcs._core.common import RobotPlatform
7+
from rcs.envs.base import ControlMode, RelativeTo
8+
from rcs_so101.creators import RCSSO101EnvCreator, SO101SimEnvCreator
9+
10+
logger = logging.getLogger(__name__)
11+
logger.setLevel(logging.INFO)
12+
13+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
14+
15+
16+
def main():
17+
18+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
19+
env_rel = RCSSO101EnvCreator()(
20+
id="so101_follower",
21+
urdf_path="/home/tobi/coding/lerobot/so101_new_calib.urdf",
22+
port="/dev/ttyACM0",
23+
calibration_dir="/home/tobi/coding/lerobot-container/calibration/robots/so101_follower/ninja_follower.json",
24+
# max_relative_movement=(0.5, np.deg2rad(90)),
25+
relative_to=RelativeTo.LAST_STEP,
26+
)
27+
else:
28+
cfg = sim.SimRobotConfig()
29+
cfg.robot_type = rcs.common.RobotType.SO101
30+
cfg.actuators = ["1", "2", "3", "4", "5"]
31+
cfg.joints = ["1", "2", "3", "4", "5"]
32+
cfg.arm_collision_geoms = []
33+
cfg.attachment_site = "gripper"
34+
35+
grp_cfg = sim.SimGripperConfig()
36+
grp_cfg.actuator = "6"
37+
grp_cfg.joint = "6"
38+
grp_cfg.collision_geoms = []
39+
grp_cfg.collision_geoms_fingers = []
40+
41+
env_rel = SO101SimEnvCreator()(
42+
control_mode=ControlMode.JOINTS,
43+
urdf_path="/home/tobi/coding/lerobot/so101_new_calib.urdf",
44+
robot_cfg=cfg,
45+
collision_guard=False,
46+
mjcf="/home/tobi/coding/lerobot/SO-ARM100/Simulation/SO101/scene.xml",
47+
gripper_cfg=grp_cfg,
48+
# camera_set_cfg=default_mujoco_cameraset_cfg(),
49+
max_relative_movement=None,
50+
# max_relative_movement=10.0,
51+
# max_relative_movement=0.5,
52+
relative_to=RelativeTo.LAST_STEP,
53+
)
54+
env_rel.get_wrapper_attr("sim").open_gui()
55+
56+
for _ in range(10):
57+
obs, info = env_rel.reset()
58+
for _ in range(100):
59+
# sample random relative action and execute it
60+
act = env_rel.action_space.sample()
61+
print(act)
62+
# act["gripper"] = 1.0
63+
obs, reward, terminated, truncated, info = env_rel.step(act)
64+
print(obs)
65+
if truncated or terminated:
66+
logger.info("Truncated or terminated!")
67+
return
68+
logger.info(act["gripper"])
69+
sleep(1.0)
70+
71+
72+
if __name__ == "__main__":
73+
main()

0 commit comments

Comments
 (0)