fix lack of collision scaling in pybullet URDF/SDF files (only graphics meshes supported scaling, collision objects ignored scaling)

This commit is contained in:
Erwin Coumans
2017-02-28 16:30:57 -08:00
parent 0131754173
commit 89e8e30de6

View File

@@ -704,6 +704,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
}
btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface,true,true);
trimesh->setLocalScaling(collision->m_geometry.m_meshScale);
shape = trimesh;
} else
{
@@ -713,6 +714,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
convexHull->optimizeConvexHull();
//convexHull->initializePolyhedralFeatures();
convexHull->setMargin(gUrdfDefaultCollisionMargin);
convexHull->setLocalScaling(collision->m_geometry.m_meshScale);
shape = convexHull;
}
} else