Implement first draft of pybullet.createVisualShape and add createVisualShape.py example

add normals to duck.obj for nicer appearance
fix plane100.urdf (so collision shape matches visual shape size)
This commit is contained in:
erwincoumans
2017-10-07 18:50:23 -07:00
parent 1034c7e720
commit cec8da3d85
12 changed files with 9018 additions and 6538 deletions

View File

@@ -905,7 +905,7 @@ void OpenGLGuiHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWor
B3_PROFILE("write all InstanceTransformToCPU");
for (int i = 0; i<numCollisionObjects; i++)
{
B3_PROFILE("writeSingleInstanceTransformToCPU");
//B3_PROFILE("writeSingleInstanceTransformToCPU");
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
btVector3 pos = colObj->getWorldTransform().getOrigin();
btQuaternion orn = colObj->getWorldTransform().getRotation();