move zipfFileIO into own header
route loadTextureFile from fileIO plugin fix B3_ENABLE_FILEIO_PLUGIN logic
This commit is contained in:
@@ -87,7 +87,8 @@ struct UrdfRenderingInterface
|
||||
virtual void render(const float viewMat[16], const float projMat[16]) = 0;
|
||||
|
||||
///load a texture from file, in png or other popular/supported format
|
||||
virtual int loadTextureFile(const char* filename) = 0;
|
||||
//virtual int loadTextureFile(const char* filename) = 0;
|
||||
virtual int loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO)=0;
|
||||
|
||||
///register a texture using an in-memory pixel buffer of a given width and height
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height) = 0;
|
||||
|
||||
@@ -77,7 +77,8 @@
|
||||
#include "plugins/tinyRendererPlugin/tinyRendererPlugin.h"
|
||||
#endif
|
||||
|
||||
#ifndef B3_ENABLE_FILEIO_PLUGIN
|
||||
|
||||
#ifdef B3_ENABLE_FILEIO_PLUGIN
|
||||
#include "plugins/fileIOPlugin/fileIOPlugin.h"
|
||||
#endif//B3_DISABLE_FILEIO_PLUGIN
|
||||
|
||||
@@ -9911,7 +9912,7 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
|
||||
int uid = -1;
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
uid = m_data->m_pluginManager.getRenderInterface()->loadTextureFile(relativeFileName);
|
||||
uid = m_data->m_pluginManager.getRenderInterface()->loadTextureFile(relativeFileName, fileIO);
|
||||
}
|
||||
if (uid >= 0)
|
||||
{
|
||||
@@ -9920,7 +9921,36 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
|
||||
|
||||
{
|
||||
int width, height, n;
|
||||
unsigned char* imageData = stbi_load(relativeFileName, &width, &height, &n, 3);
|
||||
unsigned char* imageData = 0;
|
||||
|
||||
CommonFileIOInterface* fileIO = m_data->m_pluginManager.getFileIOInterface();
|
||||
if (fileIO)
|
||||
{
|
||||
b3AlignedObjectArray<char> buffer;
|
||||
buffer.reserve(1024);
|
||||
int fileId = fileIO->fileOpen(relativeFileName,"rb");
|
||||
if (fileId>=0)
|
||||
{
|
||||
int size = fileIO->getFileSize(fileId);
|
||||
if (size>0)
|
||||
{
|
||||
buffer.resize(size);
|
||||
int actual = fileIO->fileRead(fileId,&buffer[0],size);
|
||||
if (actual != size)
|
||||
{
|
||||
b3Warning("image filesize mismatch!\n");
|
||||
buffer.resize(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (buffer.size())
|
||||
{
|
||||
imageData = stbi_load_from_memory((const unsigned char*)&buffer[0], buffer.size(), &width, &height, &n, 3);
|
||||
}
|
||||
} else
|
||||
{
|
||||
imageData = stbi_load(relativeFileName, &width, &height, &n, 3);
|
||||
}
|
||||
|
||||
if (imageData)
|
||||
{
|
||||
|
||||
@@ -1317,12 +1317,40 @@ int EGLRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
|
||||
return m_data->m_textures.size() - 1;
|
||||
}
|
||||
|
||||
int EGLRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
int EGLRendererVisualShapeConverter::loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO)
|
||||
{
|
||||
B3_PROFILE("loadTextureFile");
|
||||
int width, height, n;
|
||||
unsigned char* image = 0;
|
||||
image = stbi_load(filename, &width, &height, &n, 3);
|
||||
|
||||
if (fileIO)
|
||||
{
|
||||
b3AlignedObjectArray<char> buffer;
|
||||
buffer.reserve(1024);
|
||||
int fileId = fileIO->fileOpen(filename,"rb");
|
||||
if (fileId>=0)
|
||||
{
|
||||
int size = fileIO->getFileSize(fileId);
|
||||
if (size>0)
|
||||
{
|
||||
buffer.resize(size);
|
||||
int actual = fileIO->fileRead(fileId,&buffer[0],size);
|
||||
if (actual != size)
|
||||
{
|
||||
b3Warning("image filesize mismatch!\n");
|
||||
buffer.resize(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (buffer.size())
|
||||
{
|
||||
image = stbi_load_from_memory((const unsigned char*)&buffer[0], buffer.size(), &width, &height, &n, 3);
|
||||
}
|
||||
} else
|
||||
{
|
||||
image = stbi_load(filename, &width, &height, &n, 3);
|
||||
}
|
||||
|
||||
if (image && (width >= 0) && (height >= 0))
|
||||
{
|
||||
return registerTexture(image, width, height);
|
||||
|
||||
@@ -48,7 +48,7 @@ struct EGLRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
virtual void render();
|
||||
virtual void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
virtual int loadTextureFile(const char* filename);
|
||||
virtual int loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO);
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height);
|
||||
|
||||
virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]);
|
||||
|
||||
@@ -9,247 +9,11 @@
|
||||
#include "../../../Utils/b3BulletDefaultFileIO.h"
|
||||
|
||||
|
||||
#include "zipFileIO.h"
|
||||
|
||||
//#define B3_USE_ZLIB
|
||||
#ifdef B3_USE_ZLIB
|
||||
|
||||
#include "minizip/unzip.h"
|
||||
|
||||
struct MyFileIO : public CommonFileIOInterface
|
||||
{
|
||||
std::string m_zipfileName;
|
||||
|
||||
unzFile m_fileHandles[FILEIO_MAX_FILES];
|
||||
int m_numFileHandles;
|
||||
|
||||
MyFileIO(const char* zipfileName)
|
||||
:m_zipfileName(zipfileName),
|
||||
m_numFileHandles(0)
|
||||
{
|
||||
for (int i=0;i<FILEIO_MAX_FILES;i++)
|
||||
{
|
||||
m_fileHandles[i]=0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static bool FileIOPluginFindFile(void* userPtr, const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
MyFileIO* fileIo = (MyFileIO*) userPtr;
|
||||
return fileIo->findFile(orgFileName, relativeFileName, maxRelativeFileNameMaxLen);
|
||||
}
|
||||
|
||||
virtual ~MyFileIO()
|
||||
{
|
||||
}
|
||||
virtual int fileOpen(const char* fileName, const char* mode)
|
||||
{
|
||||
//search a free slot
|
||||
int slot = -1;
|
||||
for (int i=0;i<FILEIO_MAX_FILES;i++)
|
||||
{
|
||||
if (m_fileHandles[i]==0)
|
||||
{
|
||||
slot=i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (slot>=0)
|
||||
{
|
||||
unzFile zipfile;
|
||||
unz_global_info m_global_info;
|
||||
zipfile = unzOpen(m_zipfileName.c_str());
|
||||
if (zipfile == NULL)
|
||||
{
|
||||
printf("%s: not found\n", m_zipfileName.c_str());
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
int result = 0;
|
||||
result = unzGetGlobalInfo(zipfile, &m_global_info );
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("could not read file global info from %s\n", m_zipfileName.c_str());
|
||||
unzClose(zipfile);
|
||||
zipfile = 0;
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
m_fileHandles[slot] = zipfile;
|
||||
}
|
||||
}
|
||||
if (slot >=0)
|
||||
{
|
||||
int result = unzLocateFile(zipfile, fileName, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
unz_file_info info;
|
||||
result = unzGetCurrentFileInfo(zipfile, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("unzGetCurrentFileInfo() != UNZ_OK (%d)\n", result);
|
||||
slot=-1;
|
||||
}
|
||||
else
|
||||
{
|
||||
result = unzOpenCurrentFile(zipfile);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
} else
|
||||
{
|
||||
slot=-1;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return slot;
|
||||
}
|
||||
virtual int fileRead(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int result = -1;
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
result = unzReadCurrentFile(f, destBuffer,numBytes);
|
||||
//::fread(destBuffer, 1, numBytes, f);
|
||||
}
|
||||
}
|
||||
return result;
|
||||
|
||||
}
|
||||
virtual int fileWrite(int fileHandle,const char* sourceBuffer, int numBytes)
|
||||
{
|
||||
#if 0
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
FILE* f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
return ::fwrite(sourceBuffer, 1, numBytes,m_fileHandles[fileHandle]);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return -1;
|
||||
}
|
||||
virtual void fileClose(int fileHandle)
|
||||
{
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unzClose(f);
|
||||
m_fileHandles[fileHandle]=0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
virtual bool findResourcePath(const char* fileName, char* relativeFileName, int relativeFileNameSizeInBytes)
|
||||
{
|
||||
return b3ResourcePath::findResourcePath(fileName, relativeFileName, relativeFileNameSizeInBytes, MyFileIO::FileIOPluginFindFile, this);
|
||||
}
|
||||
|
||||
|
||||
virtual bool findFile(const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
int fileHandle = -1;
|
||||
fileHandle = fileOpen(orgFileName, "rb");
|
||||
if (fileHandle>=0)
|
||||
{
|
||||
//printf("original file found: [%s]\n", orgFileName);
|
||||
sprintf(relativeFileName, "%s", orgFileName);
|
||||
fileClose(fileHandle);
|
||||
return true;
|
||||
}
|
||||
|
||||
//printf("Trying various directories, relative to current working directory\n");
|
||||
const char* prefix[] = {"./", "./data/", "../data/", "../../data/", "../../../data/", "../../../../data/"};
|
||||
int numPrefixes = sizeof(prefix) / sizeof(const char*);
|
||||
|
||||
int f = 0;
|
||||
bool fileFound = false;
|
||||
|
||||
for (int i = 0; !f && i < numPrefixes; i++)
|
||||
{
|
||||
#ifdef _MSC_VER
|
||||
sprintf_s(relativeFileName, maxRelativeFileNameMaxLen, "%s%s", prefix[i], orgFileName);
|
||||
#else
|
||||
sprintf(relativeFileName, "%s%s", prefix[i], orgFileName);
|
||||
#endif
|
||||
f = fileOpen(relativeFileName, "rb");
|
||||
if (f>=0)
|
||||
{
|
||||
fileFound = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (f>=0)
|
||||
{
|
||||
fileClose(f);
|
||||
}
|
||||
|
||||
return fileFound;
|
||||
}
|
||||
virtual char* readLine(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int numRead = 0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
//return ::fgets(destBuffer, numBytes, m_fileHandles[fileHandle]);
|
||||
char c = 0;
|
||||
do
|
||||
{
|
||||
fileRead(fileHandle,&c,1);
|
||||
if (c && c!='\n')
|
||||
{
|
||||
if (c!=13)
|
||||
{
|
||||
destBuffer[numRead++]=c;
|
||||
} else
|
||||
{
|
||||
destBuffer[numRead++]=0;
|
||||
}
|
||||
}
|
||||
} while (c != 0 && c != '\n' && numRead<(numBytes-1));
|
||||
}
|
||||
}
|
||||
if (numRead<numBytes && numRead>0)
|
||||
{
|
||||
destBuffer[numRead]=0;
|
||||
return &destBuffer[0];
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
virtual int getFileSize(int fileHandle)
|
||||
{
|
||||
int size=0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < FILEIO_MAX_FILES)
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unz_file_info info;
|
||||
int result = unzGetCurrentFileInfo(f, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
size = info.uncompressed_size;
|
||||
}
|
||||
}
|
||||
}
|
||||
return size;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
typedef ZipFileIO MyFileIO;
|
||||
#else
|
||||
typedef b3BulletDefaultFileIO MyFileIO;
|
||||
#endif
|
||||
|
||||
238
examples/SharedMemory/plugins/fileIOPlugin/zipFileIO.h
Normal file
238
examples/SharedMemory/plugins/fileIOPlugin/zipFileIO.h
Normal file
@@ -0,0 +1,238 @@
|
||||
|
||||
#include "minizip/unzip.h"
|
||||
|
||||
#define B3_ZIP_FILEIO_MAX_FILES 1024
|
||||
|
||||
struct ZipFileIO : public CommonFileIOInterface
|
||||
{
|
||||
std::string m_zipfileName;
|
||||
|
||||
unzFile m_fileHandles[B3_ZIP_FILEIO_MAX_FILES ];
|
||||
int m_numFileHandles;
|
||||
|
||||
ZipFileIO(const char* zipfileName)
|
||||
:m_zipfileName(zipfileName),
|
||||
m_numFileHandles(0)
|
||||
{
|
||||
for (int i=0;i<B3_ZIP_FILEIO_MAX_FILES ;i++)
|
||||
{
|
||||
m_fileHandles[i]=0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static bool FileIOPluginFindFile(void* userPtr, const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
ZipFileIO* fileIo = (ZipFileIO*) userPtr;
|
||||
return fileIo->findFile(orgFileName, relativeFileName, maxRelativeFileNameMaxLen);
|
||||
}
|
||||
|
||||
virtual ~ZipFileIO()
|
||||
{
|
||||
}
|
||||
virtual int fileOpen(const char* fileName, const char* mode)
|
||||
{
|
||||
//search a free slot
|
||||
int slot = -1;
|
||||
for (int i=0;i<B3_ZIP_FILEIO_MAX_FILES ;i++)
|
||||
{
|
||||
if (m_fileHandles[i]==0)
|
||||
{
|
||||
slot=i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (slot>=0)
|
||||
{
|
||||
unzFile zipfile;
|
||||
unz_global_info m_global_info;
|
||||
zipfile = unzOpen(m_zipfileName.c_str());
|
||||
if (zipfile == NULL)
|
||||
{
|
||||
printf("%s: not found\n", m_zipfileName.c_str());
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
int result = 0;
|
||||
result = unzGetGlobalInfo(zipfile, &m_global_info );
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("could not read file global info from %s\n", m_zipfileName.c_str());
|
||||
unzClose(zipfile);
|
||||
zipfile = 0;
|
||||
slot = -1;
|
||||
} else
|
||||
{
|
||||
m_fileHandles[slot] = zipfile;
|
||||
}
|
||||
}
|
||||
if (slot >=0)
|
||||
{
|
||||
int result = unzLocateFile(zipfile, fileName, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
unz_file_info info;
|
||||
result = unzGetCurrentFileInfo(zipfile, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result != UNZ_OK)
|
||||
{
|
||||
printf("unzGetCurrentFileInfo() != UNZ_OK (%d)\n", result);
|
||||
slot=-1;
|
||||
}
|
||||
else
|
||||
{
|
||||
result = unzOpenCurrentFile(zipfile);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
} else
|
||||
{
|
||||
slot=-1;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return slot;
|
||||
}
|
||||
virtual int fileRead(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int result = -1;
|
||||
if (fileHandle>=0 && fileHandle < B3_ZIP_FILEIO_MAX_FILES )
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
result = unzReadCurrentFile(f, destBuffer,numBytes);
|
||||
//::fread(destBuffer, 1, numBytes, f);
|
||||
}
|
||||
}
|
||||
return result;
|
||||
|
||||
}
|
||||
virtual int fileWrite(int fileHandle,const char* sourceBuffer, int numBytes)
|
||||
{
|
||||
#if 0
|
||||
if (fileHandle>=0 && fileHandle < B3_ZIP_FILEIO_MAX_FILES )
|
||||
{
|
||||
FILE* f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
return ::fwrite(sourceBuffer, 1, numBytes,m_fileHandles[fileHandle]);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return -1;
|
||||
}
|
||||
virtual void fileClose(int fileHandle)
|
||||
{
|
||||
if (fileHandle>=0 && fileHandle < B3_ZIP_FILEIO_MAX_FILES )
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unzClose(f);
|
||||
m_fileHandles[fileHandle]=0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
virtual bool findResourcePath(const char* fileName, char* relativeFileName, int relativeFileNameSizeInBytes)
|
||||
{
|
||||
return b3ResourcePath::findResourcePath(fileName, relativeFileName, relativeFileNameSizeInBytes, ZipFileIO::FileIOPluginFindFile, this);
|
||||
}
|
||||
|
||||
|
||||
virtual bool findFile(const char* orgFileName, char* relativeFileName, int maxRelativeFileNameMaxLen)
|
||||
{
|
||||
int fileHandle = -1;
|
||||
fileHandle = fileOpen(orgFileName, "rb");
|
||||
if (fileHandle>=0)
|
||||
{
|
||||
//printf("original file found: [%s]\n", orgFileName);
|
||||
sprintf(relativeFileName, "%s", orgFileName);
|
||||
fileClose(fileHandle);
|
||||
return true;
|
||||
}
|
||||
|
||||
//printf("Trying various directories, relative to current working directory\n");
|
||||
const char* prefix[] = {"./", "./data/", "../data/", "../../data/", "../../../data/", "../../../../data/"};
|
||||
int numPrefixes = sizeof(prefix) / sizeof(const char*);
|
||||
|
||||
int f = 0;
|
||||
bool fileFound = false;
|
||||
|
||||
for (int i = 0; !f && i < numPrefixes; i++)
|
||||
{
|
||||
#ifdef _MSC_VER
|
||||
sprintf_s(relativeFileName, maxRelativeFileNameMaxLen, "%s%s", prefix[i], orgFileName);
|
||||
#else
|
||||
sprintf(relativeFileName, "%s%s", prefix[i], orgFileName);
|
||||
#endif
|
||||
f = fileOpen(relativeFileName, "rb");
|
||||
if (f>=0)
|
||||
{
|
||||
fileFound = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (f>=0)
|
||||
{
|
||||
fileClose(f);
|
||||
}
|
||||
|
||||
return fileFound;
|
||||
}
|
||||
virtual char* readLine(int fileHandle, char* destBuffer, int numBytes)
|
||||
{
|
||||
int numRead = 0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < B3_ZIP_FILEIO_MAX_FILES )
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
//return ::fgets(destBuffer, numBytes, m_fileHandles[fileHandle]);
|
||||
char c = 0;
|
||||
do
|
||||
{
|
||||
fileRead(fileHandle,&c,1);
|
||||
if (c && c!='\n')
|
||||
{
|
||||
if (c!=13)
|
||||
{
|
||||
destBuffer[numRead++]=c;
|
||||
} else
|
||||
{
|
||||
destBuffer[numRead++]=0;
|
||||
}
|
||||
}
|
||||
} while (c != 0 && c != '\n' && numRead<(numBytes-1));
|
||||
}
|
||||
}
|
||||
if (numRead<numBytes && numRead>0)
|
||||
{
|
||||
destBuffer[numRead]=0;
|
||||
return &destBuffer[0];
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
virtual int getFileSize(int fileHandle)
|
||||
{
|
||||
int size=0;
|
||||
|
||||
if (fileHandle>=0 && fileHandle < B3_ZIP_FILEIO_MAX_FILES )
|
||||
{
|
||||
unzFile f = m_fileHandles[fileHandle];
|
||||
if (f)
|
||||
{
|
||||
unz_file_info info;
|
||||
int result = unzGetCurrentFileInfo(f, &info, NULL, 0, NULL, 0, NULL, 0);
|
||||
if (result == UNZ_OK)
|
||||
{
|
||||
size = info.uncompressed_size;
|
||||
}
|
||||
}
|
||||
}
|
||||
return size;
|
||||
}
|
||||
|
||||
};
|
||||
@@ -1170,12 +1170,39 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
|
||||
return m_data->m_textures.size() - 1;
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO)
|
||||
{
|
||||
B3_PROFILE("loadTextureFile");
|
||||
int width, height, n;
|
||||
unsigned char* image = 0;
|
||||
image = stbi_load(filename, &width, &height, &n, 3);
|
||||
if (fileIO)
|
||||
{
|
||||
b3AlignedObjectArray<char> buffer;
|
||||
buffer.reserve(1024);
|
||||
int fileId = fileIO->fileOpen(filename,"rb");
|
||||
if (fileId>=0)
|
||||
{
|
||||
int size = fileIO->getFileSize(fileId);
|
||||
if (size>0)
|
||||
{
|
||||
buffer.resize(size);
|
||||
int actual = fileIO->fileRead(fileId,&buffer[0],size);
|
||||
if (actual != size)
|
||||
{
|
||||
b3Warning("image filesize mismatch!\n");
|
||||
buffer.resize(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (buffer.size())
|
||||
{
|
||||
image = stbi_load_from_memory((const unsigned char*)&buffer[0], buffer.size(), &width, &height, &n, 3);
|
||||
}
|
||||
} else
|
||||
{
|
||||
image = stbi_load(filename, &width, &height, &n, 3);
|
||||
}
|
||||
|
||||
if (image && (width >= 0) && (height >= 0))
|
||||
{
|
||||
return registerTexture(image, width, height);
|
||||
|
||||
@@ -47,7 +47,7 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
virtual void render();
|
||||
virtual void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
virtual int loadTextureFile(const char* filename);
|
||||
virtual int loadTextureFile(const char* filename, struct CommonFileIOInterface* fileIO);
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height);
|
||||
|
||||
virtual void syncTransform(int shapeUid, const class btTransform& worldTransform, const class btVector3& localScaling);
|
||||
|
||||
Reference in New Issue
Block a user