summaryrefslogtreecommitdiff
path: root/examples/pybullet
diff options
context:
space:
mode:
authorDamian Bemben <dbemben1@sheffield.ac.uk>2019-03-10 22:41:40 +0000
committerGitHub <noreply@github.com>2019-03-10 22:41:40 +0000
commitb027bc92df7c2ffd625a9205656bfc584777c91f (patch)
tree7f39349eaf87d0eec5463157d03d1b3046e4fcdf /examples/pybullet
parent31ce4e0e57ddb2bc8a23ebc371b627eaff813aa3 (diff)
downloadbullet3-b027bc92df7c2ffd625a9205656bfc584777c91f.tar.gz
Fixing issue where mass of motors is uneven
Mass of motors was being tilted to the left, due to FL hip motor and RL hip motor having a mass of 1.095 and FR hip motor and BR hip motor having a mass of 0.241. This led to issues with the laikago tilting. May require further investigation to see if the laikago is at the proper center of mass!
Diffstat (limited to 'examples/pybullet')
-rw-r--r--examples/pybullet/gym/pybullet_data/laikago/laikago.urdf4
1 files changed, 2 insertions, 2 deletions
diff --git a/examples/pybullet/gym/pybullet_data/laikago/laikago.urdf b/examples/pybullet/gym/pybullet_data/laikago/laikago.urdf
index 62e7e47b6..57b0a59b3 100644
--- a/examples/pybullet/gym/pybullet_data/laikago/laikago.urdf
+++ b/examples/pybullet/gym/pybullet_data/laikago/laikago.urdf
@@ -36,7 +36,7 @@
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0.02 0 0"/>
- <mass value="0.241"/>
+ <mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
@@ -262,7 +262,7 @@
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0.02 0 0"/>
- <mass value="0.241"/>
+ <mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>