Skip to content

Commit 1bbfd55

Browse files
committed
Merge branch 'master' into krack/include_models
2 parents 6557fc3 + 70e7774 commit 1bbfd55

34 files changed

+1405
-529
lines changed

pyproject.toml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,7 @@ dependencies = ["websockets>=11.0",
1010
"requests~=2.31",
1111
"numpy",
1212
"typer~=0.9",
13-
"pydantic~=2.6",
1413
"gymnasium~=0.29.1",
15-
"pydantic_yaml~=1.3",
1614
"absl-py~=2.1",
1715
"etils[epath]>=1.7.0",
1816
"glfw~=2.7",
@@ -27,6 +25,8 @@ dependencies = ["websockets>=11.0",
2725
"mujoco==3.2.6",
2826
# NOTE: Same for pinocchio (pin)
2927
"pin==2.7.0",
28+
"tilburg-hand",
29+
"digit-interface",
3030
]
3131
readme = "README.md"
3232
maintainers = [

python/examples/env_cartesian_control.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ def main():
6767
robot_cfg=default_fr3_sim_robot_cfg(),
6868
collision_guard=False,
6969
gripper_cfg=default_fr3_sim_gripper_cfg(),
70-
camera_set_cfg=default_mujoco_cameraset_cfg(),
70+
cameras=default_mujoco_cameraset_cfg(),
7171
max_relative_movement=0.5,
7272
relative_to=RelativeTo.LAST_STEP,
7373
)
Lines changed: 101 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,101 @@
1+
import logging
2+
3+
from rcs._core.common import RobotPlatform
4+
from rcs.control.fr3_desk import FCI, ContextManager, Desk, load_creds_fr3_desk
5+
from rcs.envs.base import ControlMode, RelativeTo
6+
from rcs.envs.creators import FR3SimEnvCreator, RCSFR3EnvCreator
7+
from rcs.envs.utils import (
8+
default_digit,
9+
default_fr3_hw_gripper_cfg,
10+
default_fr3_hw_robot_cfg,
11+
default_fr3_sim_gripper_cfg,
12+
default_fr3_sim_robot_cfg,
13+
default_mujoco_cameraset_cfg,
14+
)
15+
16+
from python.rcs.camera.hw import HardwareCameraSet
17+
18+
logger = logging.getLogger(__name__)
19+
logger.setLevel(logging.INFO)
20+
21+
ROBOT_IP = "192.168.101.1"
22+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
23+
24+
25+
"""
26+
Create a .env file in the same directory as this file with the following content:
27+
FR3_USERNAME=<username on franka desk>
28+
FR3_PASSWORD=<password on franka desk>
29+
30+
When you use a real FR3 you first need to unlock its joints using the following cli script:
31+
32+
python -m rcs fr3 unlock <ip>
33+
34+
or put it into guiding mode using:
35+
36+
python -m rcs fr3 guiding-mode <ip>
37+
38+
When you are done you lock it again using:
39+
40+
python -m rcs fr3 lock <ip>
41+
42+
or even shut it down using:
43+
44+
python -m rcs fr3 shutdown <ip>
45+
"""
46+
47+
48+
def main():
49+
resource_manger: FCI | ContextManager
50+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
51+
user, pw = load_creds_fr3_desk()
52+
resource_manger = FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False)
53+
else:
54+
resource_manger = ContextManager()
55+
with resource_manger:
56+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
57+
env_rel = RCSFR3EnvCreator()(
58+
ip=ROBOT_IP,
59+
control_mode=ControlMode.CARTESIAN_TQuat,
60+
robot_cfg=default_fr3_hw_robot_cfg(),
61+
collision_guard="lab",
62+
camera_set=HardwareCameraSet(default_digit({"digit_0": "D21182"})),
63+
gripper_cfg=default_fr3_hw_gripper_cfg(),
64+
max_relative_movement=0.5,
65+
relative_to=RelativeTo.LAST_STEP,
66+
)
67+
else:
68+
env_rel = FR3SimEnvCreator()(
69+
control_mode=ControlMode.CARTESIAN_TQuat,
70+
robot_cfg=default_fr3_sim_robot_cfg(),
71+
collision_guard=False,
72+
gripper_cfg=default_fr3_sim_gripper_cfg(),
73+
cameras=default_mujoco_cameraset_cfg(),
74+
max_relative_movement=0.5,
75+
relative_to=RelativeTo.LAST_STEP,
76+
)
77+
env_rel.get_wrapper_attr("sim").open_gui()
78+
79+
env_rel.reset()
80+
print(env_rel.unwrapped.robot.get_cartesian_position()) # type: ignore
81+
82+
for _ in range(10):
83+
for _ in range(10):
84+
# move 1cm in x direction (forward) and close gripper
85+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "gripper": 0}
86+
obs, reward, terminated, truncated, info = env_rel.step(act)
87+
if truncated or terminated:
88+
logger.info("Truncated or terminated!")
89+
return
90+
for _ in range(10):
91+
# move 1cm in negative x direction (backward) and open gripper
92+
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "gripper": 1}
93+
obs, reward, terminated, truncated, info = env_rel.step(act)
94+
if truncated or terminated:
95+
logger.info("Truncated or terminated!")
96+
return
97+
env_rel.close()
98+
99+
100+
if __name__ == "__main__":
101+
main()
Lines changed: 101 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,101 @@
1+
import logging
2+
3+
from rcs._core.common import RobotPlatform
4+
from rcs.control.fr3_desk import FCI, ContextManager, Desk, load_creds_fr3_desk
5+
from rcs.envs.base import ControlMode, RelativeTo
6+
from rcs.envs.creators import FR3SimEnvCreator, RCSFR3EnvCreator
7+
from rcs.envs.utils import (
8+
default_fr3_hw_robot_cfg,
9+
default_fr3_sim_gripper_cfg,
10+
default_fr3_sim_robot_cfg,
11+
default_mujoco_cameraset_cfg,
12+
default_tilburg_hw_hand_cfg,
13+
)
14+
15+
logger = logging.getLogger(__name__)
16+
logger.setLevel(logging.INFO)
17+
18+
ROBOT_IP = "192.168.101.1"
19+
ROBOT_INSTANCE = RobotPlatform.SIMULATION
20+
21+
22+
"""
23+
Create a .env file in the same directory as this file with the following content:
24+
FR3_USERNAME=<username on franka desk>
25+
FR3_PASSWORD=<password on franka desk>
26+
27+
When you use a real FR3 you first need to unlock its joints using the following cli script:
28+
29+
python -m rcs fr3 unlock <ip>
30+
31+
or put it into guiding mode using:
32+
33+
python -m rcs fr3 guiding-mode <ip>
34+
35+
When you are done you lock it again using:
36+
37+
python -m rcs fr3 lock <ip>
38+
39+
or even shut it down using:
40+
41+
python -m rcs fr3 shutdown <ip>
42+
"""
43+
44+
45+
def main():
46+
resource_manger: FCI | ContextManager
47+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
48+
user, pw = load_creds_fr3_desk()
49+
resource_manger = FCI(Desk(ROBOT_IP, user, pw), unlock=False, lock_when_done=False)
50+
else:
51+
resource_manger = ContextManager()
52+
with resource_manger:
53+
if ROBOT_INSTANCE == RobotPlatform.HARDWARE:
54+
env_rel = RCSFR3EnvCreator()(
55+
ip=ROBOT_IP,
56+
control_mode=ControlMode.CARTESIAN_TQuat,
57+
robot_cfg=default_fr3_hw_robot_cfg(),
58+
collision_guard="lab",
59+
gripper_cfg=default_tilburg_hw_hand_cfg(),
60+
max_relative_movement=0.5,
61+
relative_to=RelativeTo.LAST_STEP,
62+
)
63+
else:
64+
env_rel = FR3SimEnvCreator()(
65+
control_mode=ControlMode.CARTESIAN_TQuat,
66+
robot_cfg=default_fr3_sim_robot_cfg(),
67+
collision_guard=False,
68+
gripper_cfg=default_fr3_sim_gripper_cfg(),
69+
cameras=default_mujoco_cameraset_cfg(),
70+
max_relative_movement=0.5,
71+
relative_to=RelativeTo.LAST_STEP,
72+
)
73+
env_rel.get_wrapper_attr("sim").open_gui()
74+
75+
env_rel.reset()
76+
print(env_rel.unwrapped.robot.get_cartesian_position()) # type: ignore
77+
close_action = 0
78+
open_action = 1
79+
80+
for _ in range(10):
81+
for _ in range(10):
82+
# move 1cm in x direction (forward) and close gripper
83+
act = {"tquat": [0.01, 0, 0, 0, 0, 0, 1], "hand": close_action}
84+
obs, reward, terminated, truncated, info = env_rel.step(act)
85+
if truncated or terminated:
86+
logger.info("Truncated or terminated!")
87+
return
88+
from time import sleep
89+
90+
sleep(5)
91+
for _ in range(10):
92+
# move 1cm in negative x direction (backward) and open gripper
93+
act = {"tquat": [-0.01, 0, 0, 0, 0, 0, 1], "hand": open_action}
94+
obs, reward, terminated, truncated, info = env_rel.step(act)
95+
if truncated or terminated:
96+
logger.info("Truncated or terminated!")
97+
return
98+
99+
100+
if __name__ == "__main__":
101+
main()

python/examples/env_joint_control.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ def main():
6868
collision_guard=False,
6969
robot_cfg=default_fr3_sim_robot_cfg(),
7070
gripper_cfg=default_fr3_sim_gripper_cfg(),
71-
camera_set_cfg=default_mujoco_cameraset_cfg(),
71+
cameras=default_mujoco_cameraset_cfg(),
7272
max_relative_movement=np.deg2rad(5),
7373
relative_to=RelativeTo.LAST_STEP,
7474
)

python/examples/fr3.py

Lines changed: 20 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
from rcs._core.common import RobotPlatform
77
from rcs._core.hw import FR3Config, IKSolver
88
from rcs._core.sim import CameraType
9-
from rcs.camera.sim import SimCameraConfig, SimCameraSet, SimCameraSetConfig
9+
from rcs.camera.sim import SimCameraConfig, SimCameraSet
1010
from rcs.control.fr3_desk import FCI, ContextManager, Desk, load_creds_fr3_desk
1111

1212
ROBOT_IP = "192.168.101.1"
@@ -61,22 +61,33 @@ def main():
6161
simulation = sim.Sim(rcs.scenes["fr3_empty_world"]["mjb"])
6262
urdf_path = rcs.scenes["fr3_empty_world"]["urdf"]
6363
ik = rcs.common.IK(str(urdf_path))
64-
robot = rcs.sim.SimRobot(simulation, "0", ik)
6564
cfg = sim.SimRobotConfig()
65+
cfg.add_id("0")
6666
cfg.tcp_offset = rcs.common.Pose(rcs.common.FrankaHandTCPOffset())
67-
cfg.realtime = False
68-
robot.set_parameters(cfg)
67+
robot = rcs.sim.SimRobot(simulation, ik, cfg)
6968

7069
gripper_cfg_sim = sim.SimGripperConfig()
71-
gripper = sim.SimGripper(simulation, "0", gripper_cfg_sim)
70+
gripper_cfg_sim.add_id("0")
71+
gripper = sim.SimGripper(simulation, gripper_cfg_sim)
7272

7373
# add camera to have a rendering gui
7474
cameras = {
75-
"default_free": SimCameraConfig(identifier="", type=int(CameraType.default_free)),
76-
"wrist": SimCameraConfig(identifier="wrist_0", type=int(CameraType.fixed)),
75+
"default_free": SimCameraConfig(
76+
identifier="",
77+
type=CameraType.default_free,
78+
resolution_width=1280,
79+
resolution_height=720,
80+
frame_rate=20,
81+
),
82+
"wrist": SimCameraConfig(
83+
identifier="wrist_0",
84+
type=CameraType.fixed,
85+
resolution_width=640,
86+
resolution_height=480,
87+
frame_rate=30,
88+
),
7789
}
78-
cam_cfg = SimCameraSetConfig(cameras=cameras, resolution_width=1280, resolution_height=720, frame_rate=20)
79-
camera_set = SimCameraSet(simulation, cam_cfg) # noqa: F841
90+
camera_set = SimCameraSet(simulation, cameras) # noqa: F841
8091
simulation.open_gui()
8192

8293
else:

python/rcs/__init__.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,8 @@
33
import pathlib
44
import site
55

6-
from gymnasium.envs.registration import register
7-
from rcs import camera, control, envs, sim
6+
from gymnasium import register
7+
from rcs import camera, control, envs, hand, sim
88
from rcs._core import __version__, common, hw
99
from rcs.envs.creators import FR3SimplePickUpSimEnvCreator
1010

@@ -17,6 +17,9 @@
1717
for path in (pathlib.Path(site.getsitepackages()[0]) / "rcs" / "scenes").glob("*")
1818
}
1919

20+
# make submodules available
21+
__all__ = ["__doc__", "__version__", "common", "hw", "sim", "camera", "scenes", "control", "envs", "hand"]
22+
2023
# register gymnasium environments
2124
register(
2225
id="rcs/FR3SimplePickUpSim-v0",
@@ -29,6 +32,3 @@
2932
# id="rcs/FR3SimEnv-v0",
3033
# entry_point=FR3SimEnvCreator(),
3134
# )
32-
33-
# make submodules available
34-
__all__ = ["__doc__", "__version__", "common", "hw", "sim", "camera", "scenes", "control", "envs"]

python/rcs/_core/common.pyi

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ import numpy
1010
import pybind11_stubgen.typing_ext
1111

1212
__all__ = [
13+
"BaseCameraConfig",
1314
"FR3",
1415
"FrankaHandTCPOffset",
1516
"Gripper",
@@ -35,6 +36,13 @@ __all__ = [
3536
M = typing.TypeVar("M", bound=int)
3637
N = typing.TypeVar("N", bound=int)
3738

39+
class BaseCameraConfig:
40+
frame_rate: int
41+
identifier: str
42+
resolution_height: int
43+
resolution_width: int
44+
def __init__(self, identifier: str, frame_rate: int, resolution_width: int, resolution_height: int) -> None: ...
45+
3846
class Gripper:
3947
def get_normalized_width(self) -> float: ...
4048
def get_parameters(self) -> GripperConfig: ...

0 commit comments

Comments
 (0)