mani-skill-nightly 2025.6.7.814__py3-none-any.whl → 2025.6.13.2242__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- mani_skill/agents/robots/lerobot/__init__.py +0 -0
- mani_skill/agents/robots/lerobot/manipulator.py +124 -0
- mani_skill/agents/robots/so100/so_100.py +62 -11
- mani_skill/assets/robots/so100/README.md +1 -1
- mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/so100.urdf → so100.urdf} +19 -19
- mani_skill/envs/sapien_env.py +5 -1
- mani_skill/envs/sim2real_env.py +63 -61
- mani_skill/envs/tasks/digital_twins/__init__.py +1 -0
- mani_skill/envs/tasks/digital_twins/base_env.py +23 -18
- mani_skill/envs/tasks/digital_twins/so100_arm/__init__.py +1 -0
- mani_skill/envs/tasks/digital_twins/so100_arm/grasp_cube.py +423 -0
- mani_skill/vector/wrappers/gymnasium.py +1 -1
- {mani_skill_nightly-2025.6.7.814.dist-info → mani_skill_nightly-2025.6.13.2242.dist-info}/METADATA +4 -5
- {mani_skill_nightly-2025.6.7.814.dist-info → mani_skill_nightly-2025.6.13.2242.dist-info}/RECORD +54 -50
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Base.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Base.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Base_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Base_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_part1.ply +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_part1.ply.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_part2.ply +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Fixed_Jaw_part2.ply.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Lower_Arm.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Lower_Arm.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Lower_Arm_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Lower_Arm_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part1.ply +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part1.ply.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part2.ply +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part2.ply.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part3.ply +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Moving_Jaw_part3.ply.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Rotation_Pitch.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Rotation_Pitch.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Rotation_Pitch_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Rotation_Pitch_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Upper_Arm.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Upper_Arm.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Upper_Arm_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Upper_Arm_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Wrist_Pitch_Roll.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Wrist_Pitch_Roll.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Wrist_Pitch_Roll_Motor.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/meshes → meshes}/Wrist_Pitch_Roll_Motor.stl.convex.stl +0 -0
- /mani_skill/assets/robots/so100/{SO_5DOF_ARM100_8j/so100.srdf → so100.srdf} +0 -0
- {mani_skill_nightly-2025.6.7.814.dist-info → mani_skill_nightly-2025.6.13.2242.dist-info}/LICENSE +0 -0
- {mani_skill_nightly-2025.6.7.814.dist-info → mani_skill_nightly-2025.6.13.2242.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.6.7.814.dist-info → mani_skill_nightly-2025.6.13.2242.dist-info}/top_level.txt +0 -0
File without changes
|
@@ -0,0 +1,124 @@
|
|
1
|
+
"""
|
2
|
+
Code based on https://github.com/huggingface/lerobot for supporting real robot control via the unified LeRobot interface.
|
3
|
+
"""
|
4
|
+
|
5
|
+
import time
|
6
|
+
from typing import List, Optional
|
7
|
+
|
8
|
+
import numpy as np
|
9
|
+
import torch
|
10
|
+
|
11
|
+
from mani_skill.agents.base_real_agent import BaseRealAgent
|
12
|
+
from mani_skill.utils import common
|
13
|
+
from mani_skill.utils.structs.types import Array
|
14
|
+
|
15
|
+
try:
|
16
|
+
from lerobot.common.cameras.camera import Camera
|
17
|
+
from lerobot.common.motors.motors_bus import MotorNormMode
|
18
|
+
from lerobot.common.robots.robot import Robot
|
19
|
+
from lerobot.common.utils.robot_utils import busy_wait
|
20
|
+
except ImportError:
|
21
|
+
pass
|
22
|
+
|
23
|
+
|
24
|
+
class LeRobotRealAgent(BaseRealAgent):
|
25
|
+
"""
|
26
|
+
LeRobotRealAgent is a general class for controlling real robots via the LeRobot system. You simply just pass in the Robot instance you create via LeRobot and pass it here to make it work with ManiSkill Sim2Real environment interfaces.
|
27
|
+
|
28
|
+
Args:
|
29
|
+
robot (Robot): The Robot instance you create via LeRobot.
|
30
|
+
use_cached_qpos (bool): Whether to cache the fetched qpos values. If True, the qpos will be
|
31
|
+
read from the cache instead of the real robot when possible. This cache is only invalidated when
|
32
|
+
set_target_qpos or set_target_qvel is called. This can be useful if you want to easily have higher frequency (> 30Hz) control since qpos reading from the robot is
|
33
|
+
currently the slowest part of LeRobot for some of the supported motors.
|
34
|
+
"""
|
35
|
+
|
36
|
+
def __init__(self, robot: Robot, use_cached_qpos: bool = True, **kwargs):
|
37
|
+
super().__init__(**kwargs)
|
38
|
+
self._captured_sensor_data = None
|
39
|
+
self.real_robot = robot
|
40
|
+
self.use_cached_qpos = use_cached_qpos
|
41
|
+
self._cached_qpos = None
|
42
|
+
self._motor_keys: List[str] = None
|
43
|
+
|
44
|
+
if self.real_robot.name == "so100_follower":
|
45
|
+
self.real_robot.bus.motors["gripper"].norm_mode = MotorNormMode.DEGREES
|
46
|
+
|
47
|
+
def start(self):
|
48
|
+
self.real_robot.connect()
|
49
|
+
|
50
|
+
def stop(self):
|
51
|
+
self.real_robot.disconnect()
|
52
|
+
|
53
|
+
def set_target_qpos(self, qpos: Array):
|
54
|
+
self._cached_qpos = None
|
55
|
+
qpos = common.to_cpu_tensor(qpos).flatten()
|
56
|
+
qpos = torch.rad2deg(qpos)
|
57
|
+
qpos = {f"{self._motor_keys[i]}.pos": qpos[i] for i in range(len(qpos))}
|
58
|
+
# NOTE (stao): It seems the calibration from LeRobot has some offsets in some joints. We fix reading them here to match the expected behavior
|
59
|
+
if self.real_robot.name == "so100_follower":
|
60
|
+
qpos["elbow_flex.pos"] = qpos["elbow_flex.pos"] + 6.8
|
61
|
+
self.real_robot.send_action(qpos)
|
62
|
+
|
63
|
+
def reset(self, qpos: Array):
|
64
|
+
qpos = common.to_cpu_tensor(qpos)
|
65
|
+
freq = 30
|
66
|
+
target_pos = self.qpos
|
67
|
+
max_rad_per_step = 0.025
|
68
|
+
for _ in range(int(20 * freq)):
|
69
|
+
start_loop_t = time.perf_counter()
|
70
|
+
delta_step = (qpos - target_pos).clip(
|
71
|
+
min=-max_rad_per_step, max=max_rad_per_step
|
72
|
+
)
|
73
|
+
if np.linalg.norm(delta_step) <= 1e-4:
|
74
|
+
break
|
75
|
+
target_pos += delta_step
|
76
|
+
|
77
|
+
self.set_target_qpos(target_pos)
|
78
|
+
dt_s = time.perf_counter() - start_loop_t
|
79
|
+
busy_wait(1 / freq - dt_s)
|
80
|
+
|
81
|
+
def capture_sensor_data(self, sensor_names: Optional[List[str]] = None):
|
82
|
+
sensor_obs = dict()
|
83
|
+
cameras: dict[str, Camera] = self.real_robot.cameras
|
84
|
+
if sensor_names is None:
|
85
|
+
sensor_names = list(cameras.keys())
|
86
|
+
for name in sensor_names:
|
87
|
+
data = cameras[name].async_read()
|
88
|
+
# until https://github.com/huggingface/lerobot/issues/860 is resolved we temporarily assume this is RGB data only otherwise need to write a few extra if statements to check
|
89
|
+
# if isinstance(cameras[name], IntelRealSenseCamera):
|
90
|
+
sensor_obs[name] = dict(rgb=(common.to_tensor(data)).unsqueeze(0))
|
91
|
+
self._captured_sensor_data = sensor_obs
|
92
|
+
|
93
|
+
def get_sensor_data(self, sensor_names: Optional[List[str]] = None):
|
94
|
+
if self._captured_sensor_data is None:
|
95
|
+
raise RuntimeError(
|
96
|
+
"No sensor data captured yet. Please call capture_sensor_data() first."
|
97
|
+
)
|
98
|
+
if sensor_names is None:
|
99
|
+
return self._captured_sensor_data
|
100
|
+
else:
|
101
|
+
return {
|
102
|
+
k: v for k, v in self._captured_sensor_data.items() if k in sensor_names
|
103
|
+
}
|
104
|
+
|
105
|
+
def get_qpos(self):
|
106
|
+
# NOTE (stao): the slowest part of inference is reading the qpos from the robot. Each time it takes about 5-6 milliseconds, meaning control frequency is capped at 200Hz.
|
107
|
+
# and if you factor in other operations like policy inference etc. the max control frequency is typically more like 30-60 Hz.
|
108
|
+
# Moreover on the rare occassions reading qpos can take 40 milliseconds which causes the control step to fall behind the desired control frequency.
|
109
|
+
if self.use_cached_qpos and self._cached_qpos is not None:
|
110
|
+
return self._cached_qpos.clone()
|
111
|
+
qpos_deg = self.real_robot.bus.sync_read("Present_Position")
|
112
|
+
|
113
|
+
# NOTE (stao): It seems the calibration from LeRobot has some offsets in some joints. We fix reading them here to match the expected behavior
|
114
|
+
if self.real_robot.name == "so100_follower":
|
115
|
+
qpos_deg["elbow_flex"] = qpos_deg["elbow_flex"] - 6.8
|
116
|
+
if self._motor_keys is None:
|
117
|
+
self._motor_keys = list(qpos_deg.keys())
|
118
|
+
qpos_deg = common.flatten_state_dict(qpos_deg)
|
119
|
+
qpos = torch.deg2rad(torch.tensor(qpos_deg)).unsqueeze(0)
|
120
|
+
self._cached_qpos = qpos
|
121
|
+
return qpos
|
122
|
+
|
123
|
+
def get_qvel(self):
|
124
|
+
raise NotImplementedError
|
@@ -18,7 +18,7 @@ from mani_skill.utils.structs.pose import Pose
|
|
18
18
|
@register_agent()
|
19
19
|
class SO100(BaseAgent):
|
20
20
|
uid = "so100"
|
21
|
-
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/so100/
|
21
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/so100/so100.urdf"
|
22
22
|
urdf_config = dict(
|
23
23
|
_materials=dict(
|
24
24
|
gripper=dict(static_friction=2, dynamic_friction=2, restitution=0.0)
|
@@ -31,11 +31,7 @@ class SO100(BaseAgent):
|
|
31
31
|
|
32
32
|
keyframes = dict(
|
33
33
|
rest=Keyframe(
|
34
|
-
qpos=np.array([0,
|
35
|
-
pose=sapien.Pose(q=euler2quat(0, 0, np.pi / 2)),
|
36
|
-
),
|
37
|
-
elevated_turn=Keyframe(
|
38
|
-
qpos=np.array([0, 2.2, 2.75, -0.25, -np.pi / 2, 1.0]),
|
34
|
+
qpos=np.array([0, -1.5708, 1.5708, 0.66, 0, -1.1]),
|
39
35
|
pose=sapien.Pose(q=euler2quat(0, 0, np.pi / 2)),
|
40
36
|
),
|
41
37
|
zero=Keyframe(
|
@@ -44,6 +40,17 @@ class SO100(BaseAgent):
|
|
44
40
|
),
|
45
41
|
)
|
46
42
|
|
43
|
+
arm_joint_names = [
|
44
|
+
"shoulder_pan",
|
45
|
+
"shoulder_lift",
|
46
|
+
"elbow_flex",
|
47
|
+
"wrist_flex",
|
48
|
+
"wrist_roll",
|
49
|
+
]
|
50
|
+
gripper_joint_names = [
|
51
|
+
"gripper",
|
52
|
+
]
|
53
|
+
|
47
54
|
@property
|
48
55
|
def _controller_configs(self):
|
49
56
|
pd_joint_pos = PDJointPosControllerConfig(
|
@@ -56,16 +63,19 @@ class SO100(BaseAgent):
|
|
56
63
|
normalize_action=False,
|
57
64
|
)
|
58
65
|
|
66
|
+
# max delta permitted of 0.05 since the robot is not as accurate as more expensive arms
|
67
|
+
# and moving too fast can cause the robot to shake too much and damage the hardware
|
59
68
|
pd_joint_delta_pos = PDJointPosControllerConfig(
|
60
69
|
[joint.name for joint in self.robot.active_joints],
|
61
|
-
-0.
|
62
|
-
0.
|
70
|
+
[-0.05, -0.05, -0.05, -0.05, -0.05, -0.2],
|
71
|
+
[0.05, 0.05, 0.05, 0.05, 0.05, 0.2],
|
63
72
|
stiffness=[1e3] * 6,
|
64
73
|
damping=[1e2] * 6,
|
65
74
|
force_limit=100,
|
66
75
|
use_delta=True,
|
67
76
|
use_target=False,
|
68
77
|
)
|
78
|
+
|
69
79
|
pd_joint_target_delta_pos = copy.deepcopy(pd_joint_delta_pos)
|
70
80
|
pd_joint_target_delta_pos.use_target = True
|
71
81
|
|
@@ -122,8 +132,49 @@ class SO100(BaseAgent):
|
|
122
132
|
)
|
123
133
|
return torch.logical_and(lflag, rflag)
|
124
134
|
|
135
|
+
def _after_loading_articulation(self):
|
136
|
+
super()._after_loading_articulation()
|
137
|
+
# self.set_colors()
|
138
|
+
self.finger1_link = self.robot.links_map["Fixed_Jaw"]
|
139
|
+
self.finger2_link = self.robot.links_map["Moving_Jaw"]
|
140
|
+
self.finger1_tip = self.robot.links_map["Fixed_Jaw_tip"]
|
141
|
+
self.finger2_tip = self.robot.links_map["Moving_Jaw_tip"]
|
142
|
+
|
143
|
+
@property
|
144
|
+
def tcp_pos(self):
|
145
|
+
# computes the tool center point as the mid point between the the fixed and moving jaw's tips
|
146
|
+
return (self.finger1_tip.pose.p + self.finger2_tip.pose.p) / 2
|
147
|
+
|
148
|
+
def is_grasping(self, object: Actor, min_force=0.5, max_angle=110):
|
149
|
+
"""Check if the robot is grasping an object
|
150
|
+
|
151
|
+
Args:
|
152
|
+
object (Actor): The object to check if the robot is grasping
|
153
|
+
min_force (float, optional): Minimum force before the robot is considered to be grasping the object in Newtons. Defaults to 0.5.
|
154
|
+
max_angle (int, optional): Maximum angle of contact to consider grasping. Defaults to 85.
|
155
|
+
"""
|
156
|
+
l_contact_forces = self.scene.get_pairwise_contact_forces(
|
157
|
+
self.finger1_link, object
|
158
|
+
)
|
159
|
+
r_contact_forces = self.scene.get_pairwise_contact_forces(
|
160
|
+
self.finger2_link, object
|
161
|
+
)
|
162
|
+
lforce = torch.linalg.norm(l_contact_forces, axis=1)
|
163
|
+
rforce = torch.linalg.norm(r_contact_forces, axis=1)
|
164
|
+
|
165
|
+
# direction to open the gripper
|
166
|
+
ldirection = self.finger1_link.pose.to_transformation_matrix()[..., :3, 1]
|
167
|
+
rdirection = -self.finger2_link.pose.to_transformation_matrix()[..., :3, 1]
|
168
|
+
langle = common.compute_angle_between(ldirection, l_contact_forces)
|
169
|
+
rangle = common.compute_angle_between(rdirection, r_contact_forces)
|
170
|
+
lflag = torch.logical_and(
|
171
|
+
lforce >= min_force, torch.rad2deg(langle) <= max_angle
|
172
|
+
)
|
173
|
+
rflag = torch.logical_and(
|
174
|
+
rforce >= min_force, torch.rad2deg(rangle) <= max_angle
|
175
|
+
)
|
176
|
+
return torch.logical_and(lflag, rflag)
|
177
|
+
|
125
178
|
def is_static(self, threshold=0.2):
|
126
|
-
qvel = self.robot.get_qvel()[
|
127
|
-
:, :-2
|
128
|
-
] # exclude the gripper joint and gripper rotation joint.
|
179
|
+
qvel = self.robot.get_qvel()[:, :-1] # exclude the gripper joint
|
129
180
|
return torch.max(torch.abs(qvel), 1)[0] <= threshold
|
@@ -7,4 +7,4 @@ Changes made:
|
|
7
7
|
- Fixed joint tags from continuous to revolute which permit joint limits
|
8
8
|
- Fixed joint directions and orientations to match the real robot's joints
|
9
9
|
- removed spaces in link names
|
10
|
-
- manual decomposition of gripper link collision meshes into simpler meshes
|
10
|
+
- manual decomposition of gripper link collision meshes into simpler meshes
|
@@ -124,7 +124,7 @@
|
|
124
124
|
</collision>
|
125
125
|
</link>
|
126
126
|
<joint
|
127
|
-
name="
|
127
|
+
name="shoulder_pan"
|
128
128
|
type="revolute">
|
129
129
|
<origin
|
130
130
|
xyz="0 -0.0452 0.0165"
|
@@ -137,8 +137,8 @@
|
|
137
137
|
xyz="0 -1 0" />
|
138
138
|
<!-- note for the so100 arm there is no well defined effort/velocity limits at the moment -->
|
139
139
|
<limit
|
140
|
-
lower="-2.
|
141
|
-
upper="2.
|
140
|
+
lower="-2.0"
|
141
|
+
upper="2.0"
|
142
142
|
effort="0"
|
143
143
|
velocity="0" />
|
144
144
|
</joint>
|
@@ -200,20 +200,20 @@
|
|
200
200
|
</collision>
|
201
201
|
</link>
|
202
202
|
<joint
|
203
|
-
name="
|
203
|
+
name="shoulder_lift"
|
204
204
|
type="revolute">
|
205
205
|
<origin
|
206
206
|
xyz="0 0.1025 0.0306"
|
207
|
-
rpy="
|
207
|
+
rpy="0 0 0" />
|
208
208
|
<parent
|
209
209
|
link="Rotation_Pitch" />
|
210
210
|
<child
|
211
211
|
link="Upper_Arm" />
|
212
212
|
<axis
|
213
|
-
xyz="
|
213
|
+
xyz="1 0 0" />
|
214
214
|
<limit
|
215
|
-
lower="-
|
216
|
-
upper="
|
215
|
+
lower="-1.5708"
|
216
|
+
upper="1.5708"
|
217
217
|
effort="0"
|
218
218
|
velocity="0" />
|
219
219
|
</joint>
|
@@ -275,11 +275,11 @@
|
|
275
275
|
</collision>
|
276
276
|
</link>
|
277
277
|
<joint
|
278
|
-
name="
|
278
|
+
name="elbow_flex"
|
279
279
|
type="revolute">
|
280
280
|
<origin
|
281
281
|
xyz="0 0.11257 0.028"
|
282
|
-
rpy="
|
282
|
+
rpy="0 0 0" />
|
283
283
|
<parent
|
284
284
|
link="Upper_Arm" />
|
285
285
|
<child
|
@@ -287,8 +287,8 @@
|
|
287
287
|
<axis
|
288
288
|
xyz="1 0 0" />
|
289
289
|
<limit
|
290
|
-
lower="-
|
291
|
-
upper="
|
290
|
+
lower="-1.5708"
|
291
|
+
upper="1.5708"
|
292
292
|
effort="0"
|
293
293
|
velocity="0" />
|
294
294
|
</joint>
|
@@ -350,7 +350,7 @@
|
|
350
350
|
</collision>
|
351
351
|
</link>
|
352
352
|
<joint
|
353
|
-
name="
|
353
|
+
name="wrist_flex"
|
354
354
|
type="revolute">
|
355
355
|
<origin
|
356
356
|
xyz="0 0.0052 0.1349"
|
@@ -425,7 +425,7 @@
|
|
425
425
|
</collision>
|
426
426
|
</link>
|
427
427
|
<joint
|
428
|
-
name="
|
428
|
+
name="wrist_roll"
|
429
429
|
type="revolute">
|
430
430
|
<origin
|
431
431
|
xyz="0 -0.0601 0"
|
@@ -435,7 +435,7 @@
|
|
435
435
|
<child
|
436
436
|
link="Fixed_Jaw" />
|
437
437
|
<axis
|
438
|
-
xyz="0
|
438
|
+
xyz="0 1 0" />
|
439
439
|
<limit
|
440
440
|
lower="-3.14159"
|
441
441
|
upper="3.14159"
|
@@ -498,11 +498,11 @@
|
|
498
498
|
</collision>
|
499
499
|
</link>
|
500
500
|
<joint
|
501
|
-
name="
|
501
|
+
name="gripper"
|
502
502
|
type="revolute">
|
503
503
|
<origin
|
504
504
|
xyz="-0.0202 -0.0244 0"
|
505
|
-
rpy="3.
|
505
|
+
rpy="0 3.14159 -0.9" />
|
506
506
|
<parent
|
507
507
|
link="Fixed_Jaw" />
|
508
508
|
<child
|
@@ -510,8 +510,8 @@
|
|
510
510
|
<axis
|
511
511
|
xyz="0 0 1" />
|
512
512
|
<limit
|
513
|
-
lower="
|
514
|
-
upper="1.
|
513
|
+
lower="-1.1"
|
514
|
+
upper="1.1"
|
515
515
|
effort="0"
|
516
516
|
velocity="0" />
|
517
517
|
</joint>
|
mani_skill/envs/sapien_env.py
CHANGED
@@ -1224,7 +1224,11 @@ class BaseEnv(gym.Env):
|
|
1224
1224
|
"""
|
1225
1225
|
Get environment state dictionary. Override to include task information (e.g., goal)
|
1226
1226
|
"""
|
1227
|
-
|
1227
|
+
sim_state = self.scene.get_sim_state()
|
1228
|
+
controller_state = self.agent.controller.get_state()
|
1229
|
+
if len(controller_state) > 0:
|
1230
|
+
sim_state["controller"] = controller_state
|
1231
|
+
return sim_state
|
1228
1232
|
|
1229
1233
|
def get_state(self):
|
1230
1234
|
"""
|
mani_skill/envs/sim2real_env.py
CHANGED
@@ -26,7 +26,6 @@ class Sim2RealEnv(gym.Env):
|
|
26
26
|
Args:
|
27
27
|
sim_env (BaseEnv): The simulation environment that the real environment should be aligned with.
|
28
28
|
agent (BaseRealAgent): The real robot agent to control. This must be an object that inherits from BaseRealAgent.
|
29
|
-
obs_mode (str): The observation mode to use.
|
30
29
|
real_reset_function (Optional[Callable[[Sim2RealEnv, Optional[int], Optional[dict]], None]]): The function to call to reset the real robot. By default this is None and we use a default reset function which
|
31
30
|
calls the simulation reset function and resets the agent/robot qpos to whatever the simulation reset function sampled, then prompts the user to press enter before continuing running.
|
32
31
|
This function is given access to the Sim2RealEnv instance, the given seed and options dictionary similar to a standard gym reset function. The default function and example is shown below:
|
@@ -38,38 +37,40 @@ class Sim2RealEnv(gym.Env):
|
|
38
37
|
self.agent.reset(qpos=self.base_sim_env.agent.robot.qpos.cpu().flatten())
|
39
38
|
input("Press enter if the environment is reset")
|
40
39
|
|
41
|
-
|
40
|
+
sensor_data_preprocessing_function (Optional[Callable[[Dict], Dict]]): The function to call to process the sensor data returned by the BaseRealAgent.get_sensor_data function.
|
42
41
|
By default this is None and we use a default processing function which does the following for each sensor type:
|
43
42
|
- Camera: Perform a center crop of the real sensor image (rgb or depth) to have the same aspect ratio as the simulation sensor image. Then resize the image to the simulation sensor image shape using cv2.resize
|
43
|
+
|
44
|
+
skip_data_checks (bool): If False, this will reset the sim and real environments once to check if observations are aligned. It is recommended
|
45
|
+
to keep this False.
|
46
|
+
control_freq (Optional[int]): The control frequency of the real robot. By default this is None and we use the same control frequency as the simulation environment.
|
47
|
+
|
44
48
|
"""
|
45
49
|
|
46
|
-
metadata = {"render_modes": ["
|
50
|
+
metadata = {"render_modes": ["rgb_array", "sensors", "all"]}
|
47
51
|
|
48
52
|
def __init__(
|
49
53
|
self,
|
50
|
-
sim_env:
|
54
|
+
sim_env: gym.Env,
|
51
55
|
agent: BaseRealAgent,
|
52
|
-
obs_mode: str = "rgb",
|
53
56
|
real_reset_function: Optional[
|
54
57
|
Callable[["Sim2RealEnv", Optional[int], Optional[dict]], None]
|
55
58
|
] = None,
|
56
|
-
|
57
|
-
# obs_mode: Optional[str] = None,
|
58
|
-
reward_mode: Optional[str] = "none",
|
59
|
-
# control_mode: Optional[str] = None,
|
59
|
+
sensor_data_preprocessing_function: Optional[Callable[[Dict], Dict]] = None,
|
60
60
|
render_mode: Optional[str] = "sensors",
|
61
|
-
|
61
|
+
skip_data_checks: bool = False,
|
62
|
+
control_freq: Optional[int] = None,
|
62
63
|
):
|
63
64
|
self.sim_env = sim_env
|
64
65
|
self.num_envs = 1
|
65
66
|
assert (
|
66
|
-
self.sim_env.backend.sim_backend == "physx_cpu"
|
67
|
+
self.sim_env.unwrapped.backend.sim_backend == "physx_cpu"
|
67
68
|
), "For the Sim2RealEnv we expect the simulation to be using the physx_cpu simulation backend currently in order to correctly align the robot"
|
68
69
|
|
69
70
|
# copy over some sim parameters/settings
|
70
|
-
self.device = self.sim_env.backend.device
|
71
|
-
self.sim_freq = self.sim_env.sim_freq
|
72
|
-
self.control_freq = self.sim_env.control_freq
|
71
|
+
self.device = self.sim_env.unwrapped.backend.device
|
72
|
+
self.sim_freq = self.sim_env.unwrapped.sim_freq
|
73
|
+
self.control_freq = control_freq or self.sim_env.unwrapped.control_freq
|
73
74
|
|
74
75
|
# control timing
|
75
76
|
self.control_dt = 1 / self.control_freq
|
@@ -78,6 +79,8 @@ class Sim2RealEnv(gym.Env):
|
|
78
79
|
self.base_sim_env: BaseEnv = sim_env.unwrapped
|
79
80
|
"""the unwrapped simulation environment"""
|
80
81
|
|
82
|
+
obs_mode = self.base_sim_env.obs_mode
|
83
|
+
reward_mode = self.base_sim_env.reward_mode
|
81
84
|
self._reward_mode = reward_mode
|
82
85
|
self._obs_mode = obs_mode
|
83
86
|
self.reward_mode = reward_mode
|
@@ -141,52 +144,15 @@ class Sim2RealEnv(gym.Env):
|
|
141
144
|
# TODO create real controller class based on sim one?? Or can we just fake the data
|
142
145
|
self.agent._sim_agent.controller.qpos
|
143
146
|
|
144
|
-
|
145
|
-
|
146
|
-
|
147
|
-
if
|
148
|
-
|
149
|
-
|
150
|
-
|
151
|
-
|
152
|
-
|
153
|
-
|
154
|
-
def sensor_data_processing_function(sensor_data: Dict):
|
155
|
-
import cv2
|
156
|
-
|
157
|
-
for sensor_name in camera_sensor_names:
|
158
|
-
sim_sensor_cfg = self.base_sim_env._sensor_configs[sensor_name]
|
159
|
-
assert isinstance(sim_sensor_cfg, CameraConfig)
|
160
|
-
target_h, target_w = sim_sensor_cfg.height, sim_sensor_cfg.width
|
161
|
-
real_sensor_data = sensor_data[sensor_name]
|
162
|
-
|
163
|
-
# crop to same aspect ratio
|
164
|
-
for key in ["rgb", "depth"]:
|
165
|
-
if key in real_sensor_data:
|
166
|
-
img = real_sensor_data[key][0].numpy()
|
167
|
-
xy_res = img.shape[:2]
|
168
|
-
crop_res = np.min(xy_res)
|
169
|
-
cutoff = (np.max(xy_res) - crop_res) // 2
|
170
|
-
if xy_res[0] == xy_res[1]:
|
171
|
-
pass
|
172
|
-
elif np.argmax(xy_res) == 0:
|
173
|
-
img = img[cutoff:-cutoff, :, :]
|
174
|
-
else:
|
175
|
-
img = img[:, cutoff:-cutoff, :]
|
176
|
-
real_sensor_data[key] = common.to_tensor(
|
177
|
-
cv2.resize(img, (target_w, target_h))
|
178
|
-
).unsqueeze(0)
|
179
|
-
|
180
|
-
sensor_data[sensor_name] = real_sensor_data
|
181
|
-
return sensor_data
|
182
|
-
|
183
|
-
self.sensor_data_processing_function = sensor_data_processing_function
|
184
|
-
|
185
|
-
sample_sim_obs, _ = self.sim_env.reset()
|
186
|
-
sample_real_obs, _ = self.reset()
|
187
|
-
|
188
|
-
# perform checks to avoid errors in alignments
|
189
|
-
self._check_observations(sample_sim_obs, sample_real_obs)
|
147
|
+
if sensor_data_preprocessing_function is not None:
|
148
|
+
self.preprocess_sensor_data = sensor_data_preprocessing_function
|
149
|
+
|
150
|
+
if not skip_data_checks:
|
151
|
+
sample_sim_obs, _ = self.sim_env.reset()
|
152
|
+
sample_real_obs, _ = self.reset()
|
153
|
+
|
154
|
+
# perform checks to avoid errors in observation space alignment
|
155
|
+
self._check_observations(sample_sim_obs, sample_real_obs)
|
190
156
|
|
191
157
|
@property
|
192
158
|
def elapsed_steps(self):
|
@@ -289,7 +255,7 @@ class Sim2RealEnv(gym.Env):
|
|
289
255
|
data = self.agent.get_sensor_data(self._sensor_names)
|
290
256
|
# observation data needs to be processed to be the same shape in simulation
|
291
257
|
# default strategy is to do a center crop to the same shape as simulation and then resize image to the same shape as simulation
|
292
|
-
data = self.
|
258
|
+
data = self.preprocess_sensor_data(data)
|
293
259
|
return data
|
294
260
|
|
295
261
|
def _get_obs_with_sensor_data(
|
@@ -379,3 +345,39 @@ class Sim2RealEnv(gym.Env):
|
|
379
345
|
|
380
346
|
def close(self):
|
381
347
|
self.agent.stop()
|
348
|
+
|
349
|
+
def preprocess_sensor_data(
|
350
|
+
self, sensor_data: Dict, sensor_names: Optional[List[str]] = None
|
351
|
+
):
|
352
|
+
import cv2
|
353
|
+
|
354
|
+
if sensor_names is None:
|
355
|
+
sensor_names = list(sensor_data.keys())
|
356
|
+
for sensor_name in sensor_names:
|
357
|
+
sim_sensor_cfg = self.base_sim_env._sensor_configs[sensor_name]
|
358
|
+
assert isinstance(sim_sensor_cfg, CameraConfig)
|
359
|
+
target_h, target_w = sim_sensor_cfg.height, sim_sensor_cfg.width
|
360
|
+
real_sensor_data = sensor_data[sensor_name]
|
361
|
+
|
362
|
+
# crop to same aspect ratio
|
363
|
+
for key in ["rgb", "depth"]:
|
364
|
+
if key in real_sensor_data:
|
365
|
+
img = real_sensor_data[key][0].numpy()
|
366
|
+
xy_res = img.shape[:2]
|
367
|
+
crop_res = np.min(xy_res)
|
368
|
+
cutoff = (np.max(xy_res) - crop_res) // 2
|
369
|
+
if xy_res[0] == xy_res[1]:
|
370
|
+
pass
|
371
|
+
elif np.argmax(xy_res) == 0:
|
372
|
+
img = img[cutoff:-cutoff, :, :]
|
373
|
+
else:
|
374
|
+
img = img[:, cutoff:-cutoff, :]
|
375
|
+
real_sensor_data[key] = common.to_tensor(
|
376
|
+
cv2.resize(img, (target_w, target_h))
|
377
|
+
).unsqueeze(0)
|
378
|
+
|
379
|
+
sensor_data[sensor_name] = real_sensor_data
|
380
|
+
return sensor_data
|
381
|
+
|
382
|
+
def __getattr__(self, name):
|
383
|
+
return getattr(self.base_sim_env, name)
|
@@ -96,24 +96,29 @@ class BaseDigitalTwinEnv(BaseEnv):
|
|
96
96
|
super()._after_reconfigure(options)
|
97
97
|
# after reconfiguration in CPU/GPU sim we have initialized all ids of objects in the scene.
|
98
98
|
# and can now get the list of segmentation ids to keep
|
99
|
-
|
100
|
-
|
101
|
-
per_scene_ids
|
102
|
-
|
103
|
-
|
104
|
-
|
105
|
-
|
106
|
-
|
107
|
-
|
108
|
-
|
109
|
-
|
110
|
-
|
111
|
-
|
112
|
-
|
113
|
-
|
114
|
-
|
115
|
-
rgb_overlay_img
|
116
|
-
|
99
|
+
|
100
|
+
if self.rgb_overlay_mode != "none":
|
101
|
+
per_scene_ids = []
|
102
|
+
for object in self._objects_to_remove_from_greenscreen:
|
103
|
+
per_scene_ids.append(object.per_scene_id)
|
104
|
+
self._segmentation_ids_to_keep = torch.unique(
|
105
|
+
torch.concatenate(per_scene_ids)
|
106
|
+
)
|
107
|
+
self._objects_to_remove_from_greenscreen = []
|
108
|
+
|
109
|
+
# load the overlay images
|
110
|
+
for camera_name in self.rgb_overlay_paths.keys():
|
111
|
+
sensor = self._sensor_configs[camera_name]
|
112
|
+
if isinstance(sensor, CameraConfig):
|
113
|
+
if isinstance(self._rgb_overlay_images[camera_name], torch.Tensor):
|
114
|
+
continue
|
115
|
+
rgb_overlay_img = cv2.resize(
|
116
|
+
self._rgb_overlay_images[camera_name],
|
117
|
+
(sensor.width, sensor.height),
|
118
|
+
)
|
119
|
+
self._rgb_overlay_images[camera_name] = common.to_tensor(
|
120
|
+
rgb_overlay_img, device=self.device
|
121
|
+
)
|
117
122
|
|
118
123
|
def _green_sceen_rgb(self, rgb, segmentation, overlay_img):
|
119
124
|
"""returns green screened RGB data given a batch of RGB and segmentation images and one overlay image"""
|
@@ -0,0 +1 @@
|
|
1
|
+
from .grasp_cube import SO100GraspCubeEnv
|