PyBullet: add signed distance field support, with example/signedDistanceField.py

See also data\toys\concave_box.urdf and data\toys\concave_box.cdf

data\toys\concave_box.cdf was generated from concave_box.obj using
//GenerateSDF.exe -r "32 32 32" -d "-1.6 -1.6 -.6 1.6 1.6 .6" concave_box.obj
//SDF is based on code from DiscreGrid, https://github.com/InteractiveComputerGraphics/Discregrid
This commit is contained in:
Erwin Coumans
2018-04-16 22:57:43 +02:00
parent 982453abc6
commit 552cb5852a
11 changed files with 1121 additions and 24 deletions

View File

@@ -21,6 +21,7 @@ subject to the following restrictions:
#include "../ImportSTLDemo/LoadMeshFromSTL.h"
#include "../ImportColladaDemo/LoadMeshFromCollada.h"
#include "BulletCollision/CollisionShapes/btShapeHull.h"//to create a tesselation of a generic btConvexShape
#include "BulletCollision/CollisionShapes/btSdfCollisionShape.h"
#include "../../CommonInterfaces/CommonGUIHelperInterface.h"
#include "Bullet3Common/b3FileUtils.h"
#include <string>
@@ -509,6 +510,10 @@ bool findExistingMeshFile(
{
*out_type = UrdfGeometry::FILE_OBJ;
}
else if (ext == ".cdf")
{
*out_type = UrdfGeometry::FILE_CDF;
}
else
{
b3Warning("%s: invalid mesh filename extension '%s'\n", error_message_prefix.c_str(), ext.c_str());
@@ -662,7 +667,53 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
shape ->setMargin(gUrdfDefaultCollisionMargin);
break;
}
case URDF_GEOM_CDF:
{
char relativeFileName[1024];
char pathPrefix[1024];
pathPrefix[0] = 0;
if (b3ResourcePath::findResourcePath(collision->m_geometry.m_meshFileName.c_str(), relativeFileName, 1024))
{
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
btAlignedObjectArray<char> sdfData;
{
std::streampos fsize = 0;
std::ifstream file(relativeFileName, std::ios::binary);
if (file.good())
{
fsize = file.tellg();
file.seekg(0, std::ios::end);
fsize = file.tellg() - fsize;
file.seekg(0, std::ios::beg);
sdfData.resize(fsize);
int bytesRead = file.rdbuf()->sgetn(&sdfData[0], fsize);
btAssert(bytesRead == fsize);
file.close();
}
}
if (sdfData.size())
{
btSdfCollisionShape* sdfShape = new btSdfCollisionShape();
bool valid = sdfShape->initializeSDF(&sdfData[0], sdfData.size());
btAssert(valid);
if (valid)
{
shape = sdfShape;
}
else
{
delete sdfShape;
}
}
}
break;
}
case URDF_GEOM_MESH:
{
GLInstanceGraphicsShape* glmesh = 0;

View File

@@ -436,9 +436,16 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, XMLElement* g, ErrorLogger* l
geom.m_capsuleHeight = m_urdfScaling * urdfLexicalCast<double>(shape->Attribute("length"));
}
}
else if (type_name == "mesh")
else if ((type_name == "mesh") || (type_name == "cdf"))
{
geom.m_type = URDF_GEOM_MESH;
if ((type_name == "cdf"))
{
geom.m_type = URDF_GEOM_CDF;
}
else
{
geom.m_type = URDF_GEOM_MESH;
}
geom.m_meshScale.setValue(1,1,1);
std::string fn;

View File

@@ -54,7 +54,8 @@ enum UrdfGeomTypes
URDF_GEOM_CYLINDER,
URDF_GEOM_MESH,
URDF_GEOM_PLANE,
URDF_GEOM_CAPSULE, //non-standard URDF?
URDF_GEOM_CAPSULE, //non-standard URDF
URDF_GEOM_CDF,//signed-distance-field, non-standard URDF
URDF_GEOM_UNKNOWN,
};
@@ -79,6 +80,8 @@ struct UrdfGeometry
FILE_STL =1,
FILE_COLLADA =2,
FILE_OBJ =3,
FILE_CDF = 4,
};
int m_meshFileType;
std::string m_meshFileName;