Skip to content
Merged
Show file tree
Hide file tree
Changes from 6 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
51 changes: 37 additions & 14 deletions Simulation/SO101/so101_new_calib.urdf
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<?xml version='1.0' encoding='utf-8'?>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generated using onshape-to-robot -->
<!-- Onshape https://cad.onshape.com/documents/7715cc284bb430fe6dab4ffd/w/4fd0791b683777b02f8d975a/e/826c553ede3b7592eb9ca800 -->
<robot name="so101_new_calib">
Expand Down Expand Up @@ -75,7 +75,21 @@
</geometry>
</collision>
</link>

<!-- Frame baseframe (dummy link + fixed joint) -->
<link name="baseframe">
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1e-9"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="baseframe_frame" type="fixed">
<origin xyz="0.020791 0.0157608 0.0324817" rpy="2.77556e-17 -9.52796e-30 -2.64454e-46"/>
<parent link="base"/>
<child link="baseframe"/>
<axis xyz="0 0 0"/>
</joint>
<!-- Link shoulder -->
<link name="shoulder">
<inertial>
Expand Down Expand Up @@ -126,7 +140,6 @@
</geometry>
</collision>
</link>

<!-- Link upper_arm -->
<link name="upper_arm">
<inertial>
Expand Down Expand Up @@ -163,7 +176,6 @@
</geometry>
</collision>
</link>

<!-- Link lower_arm -->
<link name="lower_arm">
<inertial>
Expand Down Expand Up @@ -214,7 +226,6 @@
</geometry>
</collision>
</link>

<!-- Link wrist -->
<link name="wrist">
<inertial>
Expand Down Expand Up @@ -251,7 +262,6 @@
</geometry>
</collision>
</link>

<!-- Link gripper -->
<link name="gripper">
<inertial>
Expand Down Expand Up @@ -288,9 +298,23 @@
</geometry>
</collision>
</link>

<!-- Link jaw -->
<link name="jaw">
<!-- Frame gripperframe (dummy link + fixed joint) -->
<link name="gripperframe">
<origin xyz="0 0 0" rpy="0 -0 0"/>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1e-9"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<joint name="gripperframe_frame" type="fixed">
<origin xyz="-0.0079 -0.000218121 -0.0981274" rpy="1.5708 1.22465e-16 1.5708"/>
<parent link="gripper"/>
<child link="gripperframe"/>
<axis xyz="0 0 0"/>
</joint>
<!-- Link moving_jaw_so101_v1 -->
<link name="moving_jaw_so101_v1">
<inertial>
<origin xyz="-0.00157495 -0.0300244 0.0192755" rpy="0 0 0"/>
<mass value="0.012"/>
Expand All @@ -311,12 +335,11 @@
</geometry>
</collision>
</link>

<!-- Joint from gripper to jaw -->
<!-- Joint from gripper to moving_jaw_so101_v1 -->
<joint name="6" type="revolute">
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -5.14108e-17 -1.38655e-14"/>
<parent link="gripper"/>
<child link="jaw"/>
<child link="moving_jaw_so101_v1"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-0.174533" upper="1.74533"/>
</joint>
Expand Down Expand Up @@ -430,6 +453,6 @@
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</transmission>

</robot>
</robot>
Loading