PyBullet.loadURDF, expose flags=URDF_INITIALIZE_SAT_FEATURES

This commit is contained in:
erwincoumans
2018-06-13 15:35:56 -07:00
parent b75c63f2a2
commit 25c5e87dc2
5 changed files with 28 additions and 10 deletions

View File

@@ -474,7 +474,7 @@ bool BulletURDFImporter::getRootTransformInWorld(btTransform& rootTransformInWor
return true;
}
static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale)
static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t>& shapes, const btVector3& geomScale, int flags)
{
B3_PROFILE("createConvexHullFromShapes");
btCompoundShape* compound = new btCompoundShape();
@@ -513,7 +513,11 @@ static btCollisionShape* createConvexHullFromShapes(std::vector<tinyobj::shape_t
convexHull->recalcLocalAabb();
convexHull->optimizeConvexHull();
convexHull->initializePolyhedralFeatures();
if (flags & CUF_INITIALIZE_SAT_FEATURES)
{
convexHull->initializePolyhedralFeatures();
}
compound->addChildShape(identity,convexHull);
}
@@ -683,7 +687,10 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
btConvexHullShape* cylZShape = new btConvexHullShape(&vertices[0].x(), vertices.size(), sizeof(btVector3));
cylZShape->setMargin(gUrdfDefaultCollisionMargin);
cylZShape->recalcLocalAabb();
cylZShape->initializePolyhedralFeatures();
if (m_data->m_flags & CUF_INITIALIZE_SAT_FEATURES)
{
cylZShape->initializePolyhedralFeatures();
}
cylZShape->optimizeConvexHull();
shape = cylZShape;
}
@@ -695,7 +702,10 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
btVector3 extents = collision->m_geometry.m_boxSize;
btBoxShape* boxShape = new btBoxShape(extents*0.5f);
//btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5);
boxShape->initializePolyhedralFeatures();
if (m_data->m_flags & CUF_INITIALIZE_SAT_FEATURES)
{
boxShape->initializePolyhedralFeatures();
}
shape = boxShape;
shape ->setMargin(gUrdfDefaultCollisionMargin);
break;
@@ -779,7 +789,7 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
std::string err = tinyobj::LoadObj(shapes, collision->m_geometry.m_meshFileName.c_str());
//create a convex hull for each shape, and store it in a btCompoundShape
shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale);
shape = createConvexHullFromShapes(shapes, collision->m_geometry.m_meshScale, m_data->m_flags);
m_data->m_bulletCollisionShape2UrdfCollision.insert(shape, *collision);
return shape;
}
@@ -907,7 +917,10 @@ upAxisMat.setIdentity();
BT_PROFILE("convert btConvexHullShape");
btConvexHullShape* convexHull = new btConvexHullShape(&convertedVerts[0].getX(), convertedVerts.size(), sizeof(btVector3));
convexHull->optimizeConvexHull();
convexHull->initializePolyhedralFeatures();
if (m_data->m_flags & CUF_INITIALIZE_SAT_FEATURES)
{
convexHull->initializePolyhedralFeatures();
}
convexHull->setMargin(gUrdfDefaultCollisionMargin);
convexHull->recalcLocalAabb();
//convexHull->setLocalScaling(collision->m_geometry.m_meshScale);

View File

@@ -30,6 +30,7 @@ enum ConvertURDFFlags {
CUF_MJCF_COLORS_FROM_FILE=512,
CUF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
CUF_ENABLE_SLEEPING=2048,
CUF_INITIALIZE_SAT_FEATURES=4096,
};
struct UrdfVisualShapeCache