Skip to content

Commit

Permalink
fix lack of collision scaling in pybullet URDF/SDF files (only graphi…
Browse files Browse the repository at this point in the history
…cs meshes supported scaling, collision objects ignored scaling)
  • Loading branch information
erwincoumans committed Mar 1, 2017
1 parent 0131754 commit 89e8e30
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -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
Expand Down

0 comments on commit 89e8e30

Please sign in to comment.