From 89e8e30de6af3d074c09dfde12f70535981d735a Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 28 Feb 2017 16:30:57 -0800 Subject: [PATCH] fix lack of collision scaling in pybullet URDF/SDF files (only graphics meshes supported scaling, collision objects ignored scaling) --- examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 32281da3e..dfe49e8b6 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -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