Implement InMemoryFile for memory caching for fileIO plugin.

Support SDF loading through fileIO plugin.
Replace strcspn by C code (not crossplatform)
Add flag for loadURDF to use color from MTL file (instead from URDF link material)
pybullet.URDF_USE_MATERIAL_COLORS_FROM_MTL and pybullet.URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL
This commit is contained in:
erwincoumans
2018-10-14 12:54:34 -07:00
parent 3309ce8f6a
commit c1e20c448f
12 changed files with 511 additions and 66 deletions

View File

@@ -53,6 +53,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
meshData.m_textureImage1 = 0;
meshData.m_textureHeight = 0;
meshData.m_textureWidth = 0;
meshData.m_flags = 0;
meshData.m_isCached = false;
char relativeFileName[1024];
@@ -78,6 +79,18 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
for (int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++)
{
const tinyobj::shape_t& shape = shapes[i];
meshData.m_rgbaColor[0] = shape.material.diffuse[0];
meshData.m_rgbaColor[1] = shape.material.diffuse[1];
meshData.m_rgbaColor[2] = shape.material.diffuse[2];
meshData.m_rgbaColor[3] = shape.material.transparency;
meshData.m_flags |= B3_IMPORT_MESH_HAS_RGBA_COLOR;
meshData.m_specularColor[0] = shape.material.specular[0];
meshData.m_specularColor[1] = shape.material.specular[1];
meshData.m_specularColor[2] = shape.material.specular[2];
meshData.m_specularColor[3] = 1;
meshData.m_flags |= B3_IMPORT_MESH_HAS_SPECULAR_COLOR;
if (shape.material.diffuse_texname.length() > 0)
{
int width, height, n;

View File

@@ -3,6 +3,12 @@
#include <string>
enum b3ImportMeshDataFlags
{
B3_IMPORT_MESH_HAS_RGBA_COLOR=1,
B3_IMPORT_MESH_HAS_SPECULAR_COLOR=2,
};
struct b3ImportMeshData
{
struct GLInstanceGraphicsShape* m_gfxShape;
@@ -11,6 +17,20 @@ struct b3ImportMeshData
bool m_isCached;
int m_textureWidth;
int m_textureHeight;
double m_rgbaColor[4];
double m_specularColor[4];
int m_flags;
b3ImportMeshData()
:m_gfxShape(0),
m_textureImage1(0),
m_isCached(false),
m_textureWidth(0),
m_textureHeight(0),
m_flags(0)
{
}
};
class b3ImportMeshUtility

View File

@@ -228,24 +228,36 @@ bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase)
}
else
{
char path[1024];
fu.extractPath(relativeFileName, path, sizeof(path));
m_data->setSourceFile(relativeFileName, path);
std::fstream xml_file(relativeFileName, std::fstream::in);
while (xml_file.good())
//read file
int fileId = m_data->m_fileIO->fileOpen(relativeFileName,"r");
char destBuffer[8192];
char* line = 0;
do
{
std::string line;
std::getline(xml_file, line);
xml_string += (line + "\n");
line = m_data->m_fileIO->readLine(fileId, destBuffer, 8192);
if (line)
{
xml_string += (std::string(destBuffer) + "\n");
}
}
xml_file.close();
while (line);
m_data->m_fileIO->fileClose(fileId);
}
BulletErrorLogger loggie;
//todo: quick test to see if we can re-use the URDF parser for SDF or not
m_data->m_urdfParser.setParseSDF(true);
bool result = m_data->m_urdfParser.loadSDF(xml_string.c_str(), &loggie);
bool result = false;
if (xml_string.length())
{
result = m_data->m_urdfParser.loadSDF(xml_string.c_str(), &loggie);
}
return result;
}
@@ -861,7 +873,7 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(const UrdfColl
return shape;
}
void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<BulletURDFTexture>& texturesOut) const
void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<BulletURDFTexture>& texturesOut, struct b3ImportMeshData& meshData) const
{
BT_PROFILE("convertURDFToVisualShapeInternal");
@@ -920,7 +932,7 @@ void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visu
{
case UrdfGeometry::FILE_OBJ:
{
b3ImportMeshData meshData;
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData, m_data->m_fileIO))
{
if (meshData.m_textureImage1)
@@ -1150,16 +1162,49 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
btTransform childTrans = vis.m_linkLocalFrame;
btHashString matName(vis.m_materialName.c_str());
UrdfMaterial* const* matPtr = model.m_materials[matName];
if (matPtr)
b3ImportMeshData meshData;
convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures,meshData);
if (m_data->m_flags&CUF_USE_MATERIAL_COLORS_FROM_MTL)
{
UrdfMaterial* const mat = *matPtr;
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
UrdfMaterialColor matCol;
matCol.m_rgbaColor = mat->m_matColor.m_rgbaColor;
matCol.m_specularColor = mat->m_matColor.m_specularColor;
m_data->m_linkColors.insert(linkIndex, matCol);
if ((meshData.m_flags & B3_IMPORT_MESH_HAS_RGBA_COLOR) &&
(meshData.m_flags & B3_IMPORT_MESH_HAS_SPECULAR_COLOR))
{
UrdfMaterialColor matCol;
if (m_data->m_flags&CUF_USE_MATERIAL_TRANSPARANCY_FROM_MTL)
{
matCol.m_rgbaColor.setValue(meshData.m_rgbaColor[0],
meshData.m_rgbaColor[1],
meshData.m_rgbaColor[2],
meshData.m_rgbaColor[3]);
} else
{
matCol.m_rgbaColor.setValue(meshData.m_rgbaColor[0],
meshData.m_rgbaColor[1],
meshData.m_rgbaColor[2],
1);
}
matCol.m_specularColor.setValue(meshData.m_specularColor[0],
meshData.m_specularColor[1],
meshData.m_specularColor[2]);
m_data->m_linkColors.insert(linkIndex, matCol);
}
} else
{
if (matPtr)
{
UrdfMaterial* const mat = *matPtr;
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
UrdfMaterialColor matCol;
matCol.m_rgbaColor = mat->m_matColor.m_rgbaColor;
matCol.m_specularColor = mat->m_matColor.m_specularColor;
m_data->m_linkColors.insert(linkIndex, matCol);
}
}
convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse() * childTrans, vertices, indices, textures);
}
}
if (vertices.size() && indices.size())

View File

@@ -88,7 +88,7 @@ public:
virtual int getAllocatedTexture(int index) const;
virtual void setEnableTinyRenderer(bool enable);
void convertURDFToVisualShapeInternal(const struct UrdfVisual* visual, const char* urdfPathPrefix, const class btTransform& visualTransform, btAlignedObjectArray<struct GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<struct BulletURDFTexture>& texturesOut) const;
void convertURDFToVisualShapeInternal(const struct UrdfVisual* visual, const char* urdfPathPrefix, const class btTransform& visualTransform, btAlignedObjectArray<struct GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<struct BulletURDFTexture>& texturesOut, struct b3ImportMeshData& meshData) const;
};
#endif //BULLET_URDF_IMPORTER_H

View File

@@ -32,6 +32,8 @@ enum ConvertURDFFlags
CUF_INITIALIZE_SAT_FEATURES = 4096,
CUF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
CUF_PARSE_SENSORS = 16384,
CUF_USE_MATERIAL_COLORS_FROM_MTL = 32768,
CUF_USE_MATERIAL_TRANSPARANCY_FROM_MTL = 64738,
};
struct UrdfVisualShapeCache

View File

@@ -74,16 +74,8 @@ static bool UrdfFindMeshFile(
std::string existing_file;
{
std::string attempt = fn;
int f = fileIO->fileOpen(attempt.c_str(), "rb");
if (f>=0)
{
existing_file = attempt;
fileIO->fileClose(f);
}
}
if (existing_file.empty())
{
for (std::list<std::string>::iterator x = shorter.begin(); x != shorter.end(); ++x)
{
@@ -100,6 +92,16 @@ static bool UrdfFindMeshFile(
break;
}
}
if (existing_file.empty())
{
std::string attempt = fn;
int f = fileIO->fileOpen(attempt.c_str(), "rb");
if (f>=0)
{
existing_file = attempt;
fileIO->fileClose(f);
}
}
if (existing_file.empty())
{