fix pybullet.c compilation for Windows

add lego.urdf, duck.urdf (optimized using VHACD convex decomposition)
optimize Kiva shelf collision model (by hand, using boxes/Blender)
physics timescale toggle between  1 -> 0,25 -> 0
This commit is contained in:
erwincoumans
2016-09-24 11:25:05 -07:00
parent 0dfe20c036
commit f5e65197f4
13 changed files with 16333 additions and 38 deletions

View File

@@ -225,7 +225,8 @@ void ConvertURDF2BulletInternal(
{
btVector3 color = selectColor2();
btVector4 color = selectColor2();
u2b.getLinkColor(urdfLinkIndex,color);
/*
if (visual->material.get())
{
@@ -255,7 +256,7 @@ void ConvertURDF2BulletInternal(
btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape);
linkRigidBody = body;
world1->addRigidBody(body, bodyCollisionFilterGroup, bodyCollisionFilterMask);
world1->addRigidBody(body);
compoundShape->setUserIndex(graphicsIndex);