mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 22:00:05 +00:00
Merge remote-tracking branch 'bp/master'
This commit is contained in:
commit
60b5ffc13a
@ -6,7 +6,7 @@
|
||||
|
||||
This is the official C++ source code repository of the Bullet Physics SDK: real-time collision detection and multi-physics simulation for VR, games, visual effects, robotics, machine learning etc.
|
||||
|
||||
New in Bullet 2.85: pybullet Python bindings, improved support for robotics and VR
|
||||
New in Bullet 2.85: pybullet Python bindings, improved support for robotics and VR. Use pip install pybullet and see [PyBullet Quickstart Guide](https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.2ye70wns7io3).
|
||||
|
||||
The Bullet 2 API will stay default and up-to-date while slowly moving to a new API.
|
||||
The steps towards a new API is in a nutshell:
|
||||
|
@ -97,7 +97,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.644"/>
|
||||
<mass value="1.32"/>
|
||||
<inertia ixx=".004147" ixy=".0" ixz=".0" iyy=".040913" iyz=".0" izz=".041840"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -171,7 +171,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.644"/>
|
||||
<mass value="1.32"/>
|
||||
<inertia ixx=".004147" ixy=".0" ixz=".0" iyy=".040913" iyz=".0" izz=".041840"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -198,7 +198,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -225,7 +225,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -252,7 +252,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -279,7 +279,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -306,7 +306,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -333,7 +333,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -360,7 +360,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@ -387,7 +387,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value=".241"/>
|
||||
<mass value=".072"/>
|
||||
<inertia ixx=".00011397" ixy=".0" ixz=".0" iyy=".00011397" iyz=".0" izz=".00021765"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
Loading…
Reference in New Issue
Block a user