diff options
author | Erwin Coumans <erwin.coumans@gmail.com> | 2020-08-17 16:22:31 -0700 |
---|---|---|
committer | Erwin Coumans <erwin.coumans@gmail.com> | 2020-08-17 16:22:31 -0700 |
commit | d8d81f9ca494b8218fb0e06d1d28268f69c05969 (patch) | |
tree | 28e68f196d802ccd92d5a4a911dcb9c40608e108 | |
parent | bac8b6305dd73a6deec327f3a0f89bb51e5c6321 (diff) | |
download | bullet3-d8d81f9ca494b8218fb0e06d1d28268f69c05969.tar.gz |
laikago_toes_zup.urdf: fill in inertia values, computed as PyBullet does internally (from mass and collision volumes)
-rw-r--r-- | examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup.urdf | 26 |
1 files changed, 13 insertions, 13 deletions
diff --git a/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup.urdf b/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup.urdf index d051affb8..8ebab9123 100644 --- a/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup.urdf +++ b/examples/pybullet/gym/pybullet_data/laikago/laikago_toes_zup.urdf @@ -7,7 +7,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 0 0"/> <mass value="13.715"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.22" ixy="0" ixz="0" iyy="0.431" iyz="0" izz="0.565"/> </inertial> <visual> <origin rpy="0 0 0" xyz=" 0 0 0"/> @@ -32,7 +32,7 @@ <inertial> <origin rpy="0 0 0" xyz="0.02 0 0"/> <mass value="1.095"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy=".002" iyz="0" izz=".001"/> </inertial> <visual> @@ -67,7 +67,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.04 -0.04"/> <mass value="1.527"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.015" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.01"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -102,7 +102,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.16 -0.02"/> <mass value="0.241"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/> </inertial> <visual> <origin rpy="0 1.57079 0" xyz="0 0.0 0"/> @@ -137,7 +137,7 @@ <inertial> <origin rpy="0 0 0" xyz="-.02 0 0"/> <mass value="1.095"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -174,7 +174,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.04 -0.04"/> <mass value="1.527"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -213,7 +213,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.16 -0.02"/> <mass value="0.241"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/> </inertial> <visual> <origin rpy="0 1.57079 0" xyz="0 0 0"/> @@ -254,7 +254,7 @@ <inertial> <origin rpy="0 0 0" xyz="0.02 0 0"/> <mass value="1.095"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/> </inertial> <visual> @@ -291,7 +291,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.04 -0.04"/> <mass value="1.527"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -326,7 +326,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.16 -0.02"/> <mass value="0.241"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/> </inertial> <visual> <origin rpy="0 1.57079 0" xyz="0 0 0"/> @@ -362,7 +362,7 @@ <inertial> <origin rpy="0 0 0" xyz="-.02 0 0"/> <mass value="1.095"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -398,7 +398,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.04 -0.04"/> <mass value="1.527"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/> </inertial> <visual> <origin rpy="0 0 0" xyz="0 0 0"/> @@ -435,7 +435,7 @@ <inertial> <origin rpy="0 0 0" xyz="0 -0.16 -0.02"/> <mass value="0.241"/> - <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> + <inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/> </inertial> <visual> <origin rpy="0 1.57079 0" xyz="0 0 0"/> |