Add <inertia> for missing links in a1.urdf

Currently a few collision frames in a1.urdf ("{FL/FR/RL/RR}_upper_shoulder") do not have <inertia> defined, and pybullet loads as if they have 1kg mass. This leads to inaccurate simulation results.
This commit is contained in:
Yuxiang Yang 2020-10-06 00:28:24 -07:00 committed by GitHub
parent b12da620ab
commit 82182e1ba7
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -111,6 +111,11 @@
</joint>
<!-- this link is only for collision -->
<link name="FR_upper_shoulder">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
@ -263,6 +268,11 @@
</joint>
<!-- this link is only for collision -->
<link name="FL_upper_shoulder">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
@ -415,6 +425,11 @@
</joint>
<!-- this link is only for collision -->
<link name="RR_upper_shoulder">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
@ -567,6 +582,11 @@
</joint>
<!-- this link is only for collision -->
<link name="RL_upper_shoulder">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<geometry>