Skip to content
Open
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions mani_skill/agents/robots/so101/so_101.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,15 @@ class SO101(BaseAgent):

keyframes = dict(
rest=Keyframe(
qpos=np.array([0, -1.5708, 1.5708, 0.66, 0.0, -1.13778]), # Fully closed gripper
qpos=np.array([0, -1.5708, 1.5708, 0.66, 0.0, -10 * np.pi/180]), # Fully closed gripper
pose=sapien.Pose(q=list(euler2quat(0, 0, np.pi / 2))),
),
zero=Keyframe(
qpos=np.array([0.0] * 6),
qpos=np.array([0, 0, 0, 0, 0, 0]),
pose=sapien.Pose(q=list(euler2quat(0, 0, np.pi / 2))),
),
extended=Keyframe(
qpos=np.array([0, -0.7854, 0.7854, 0, 0, 1.16081]), # Fully open gripper
qpos=np.array([0, -0.7854, 0.7854, 0, 0, 100 * np.pi/180]), # Fully open gripper
pose=sapien.Pose(q=list(euler2quat(0, 0, np.pi / 2))),
),
)
Expand Down Expand Up @@ -107,7 +107,7 @@ def tcp_pos(self):
def tcp_pose(self):
return Pose.create_from_pq(self.tcp_pos, self.finger1_link.pose.q)

def is_grasping(self, object: Actor, min_force=0.5, max_angle=120):
def is_grasping(self, object: Actor, min_force=0.5, max_angle=110):
"""Check if the robot is grasping an object (more lenient parameters)"""
l_contact_forces = self.scene.get_pairwise_contact_forces(
self.finger1_link, object
Expand Down
2 changes: 1 addition & 1 deletion mani_skill/agents/robots/so101/so_101_real.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,4 +5,4 @@ class SO101RealAgent(LeRobotRealAgent):
SO101RealAgent is a class for controlling the SO101 real robot via the LeRobot system.
It inherits from LeRobotRealAgent and uses the same functionality with the SO101 robot configuration.
"""
pass
pass
22 changes: 11 additions & 11 deletions mani_skill/assets/robots/so101/so101.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

<!-- Materials -->
<material name="3d_printed">
<color rgba="1.0 0.82 0.12 1.0"/>
<color rgba="0.95 0.95 0.95 1.0"/>
</material>
<material name="sts3215">
<color rgba="0.1 0.1 0.1 1.0"/>
Expand Down Expand Up @@ -337,11 +337,11 @@

<!-- Joint from gripper to moving_jaw_so101_v1 -->
<joint name="gripper" type="revolute">
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -0.909 -1.41553e-15"/>
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -5.24284e-08 -1.41553e-15"/>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this e-08 value should just be 0?

<parent link="gripper_link"/>
<child link="moving_jaw_so101_v1_link"/>
<axis xyz="0 0 1"/>
<limit effort="0" velocity="10" lower="-1.13778" upper="1.16081"/>
<limit effort="10" velocity="10" lower="-0.174533" upper="2.0944"/>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we don't use effort but just checking these values of 10 are copied from the original so101 urdf, the new calibrated one here right https://github.com/TheRobotStudio/SO-ARM100/blob/main/Simulation/SO101/so101_new_calib.urdf

</joint>

<transmission name="gripper_trans">
Expand All @@ -357,7 +357,7 @@

<!-- Joint from wrist to gripper -->
<joint name="wrist_roll" type="revolute">
<origin xyz="5.55112e-17 -0.0611 0.0181" rpy="1.5708 0.0486795 3.14159"/>
<origin xyz="5.55112e-17 -0.0611 0.0181" rpy="1.5708 0 3.09159"/>
<parent link="wrist_link"/>
<child link="gripper_link"/>
<axis xyz="0 0 1"/>
Expand All @@ -377,7 +377,7 @@

<!-- Joint from lower_arm to wrist -->
<joint name="wrist_flex" type="revolute">
<origin xyz="-0.1349 0.0052 3.62355e-17" rpy="4.02456e-15 8.67362e-16 -1.5708"/>
<origin xyz="-0.1349 0.0052 3.62355e-17" rpy="4.02456e-15 8.67362e-16 -1.6708"/>
<parent link="lower_arm_link"/>
<child link="wrist_link"/>
<axis xyz="0 0 1"/>
Expand All @@ -398,7 +398,7 @@
<!-- Joint from upper_arm to lower_arm -->
<!-- Note: 5-degree calibration offset applied to joint limits -->
<joint name="elbow_flex" type="revolute">
<origin xyz="-0.11257 -0.028 1.73763e-16" rpy="-3.63608e-16 0.03 1.5708"/>
<origin xyz="-0.11257 -0.028 1.73763e-16" rpy="-3.63608e-16 8.74301e-16 1.4408"/>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

e-16 should just be 0

<parent link="upper_arm_link"/>
<child link="lower_arm_link"/>
<axis xyz="0 0 1"/>
Expand All @@ -418,7 +418,7 @@

<!-- Joint from shoulder to upper_arm -->
<joint name="shoulder_lift" type="revolute">
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 -1.728 0"/>
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 -1.6208 0.03"/>
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<axis xyz="0 0 1"/>
Expand All @@ -438,7 +438,7 @@

<!-- Joint from base to shoulder -->
<joint name="shoulder_pan" type="revolute">
<origin xyz="0.0388353 -8.97657e-09 0.0624" rpy="3.14159 4.18253e-17 -3.14159"/>
<origin xyz="0.0388353 -8.97657e-09 0.0624" rpy="3.14159 4.18253e-17 -3.20159"/>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

e-17 should be 0.

I noticed the official urdfs from the robotstudio used the e-17 values, but we should use 0 (and I'll tell them they should use 0 as well).

<parent link="base_link"/>
<child link="shoulder_link"/>
<axis xyz="0 0 1"/>
Expand All @@ -458,7 +458,7 @@

<!-- fake joints for useful data -->
<joint name="finger1_tip_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01 -0.0 -0.086"/>
<origin rpy="0 0 0" xyz="-0.002 -0.0 -0.092"/>
<parent link="gripper_link"/>
<child link="finger1_tip"/>
</joint>
Expand All @@ -471,7 +471,7 @@
</link>

<joint name="finger2_tip_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.01 -0.064 0.02"/>
<origin rpy="0 0 0" xyz="-0.01 -0.077 0.02"/>
<parent link="moving_jaw_so101_v1_link"/>
<child link="finger2_tip"/>
</joint>
Expand All @@ -483,4 +483,4 @@
</visual> -->
</link>

</robot>
</robot>
8 changes: 4 additions & 4 deletions mani_skill/envs/tasks/digital_twins/so101_arm/grasp_cube.py
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ def __init__(
] = SO101GraspCubeDomainRandomizationConfig(),
domain_randomization=True,
base_camera_settings=dict(
fov=52 * np.pi / 180,
pos=[0.5, 0.3, 0.35],
target=[0.3, 0.0, 0.1],
fov=0.8256,
pos=[0.69, 0.37, 0.28],
target=[0.185, -0.15, 0.0],
),
spawn_box_pos=[0.30, 0.05],
spawn_box_half_size=0.2 / 2,
Expand Down Expand Up @@ -264,7 +264,7 @@ def _load_scene(self, options: dict):

# a hardcoded initial joint configuration for the robot to start from
self.rest_qpos = torch.tensor(
[0.0, 0.0, 0.0, np.pi / 2, np.pi / 2, 0],
[0, 0, 0, np.pi / 2, np.pi / 2, 0],
device=self.device,
)
# hardcoded pose for the table that places it such that the robot base is at 0 and on the edge of the table.
Expand Down