expose texture unique id after loading URD file, so you can restore to the original texture after changing it to a custom texture. See also getTextureUid.py example.
This commit is contained in:
@@ -2719,6 +2719,7 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
|
||||
SaveWorldObjectData sd;
|
||||
sd.m_fileName = fileName;
|
||||
|
||||
int currentOpenGLTextureIndex = 0;
|
||||
|
||||
for (int m =0; m<u2b.getNumModels();m++)
|
||||
{
|
||||
@@ -2885,6 +2886,44 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
int startShapeIndex = 0;
|
||||
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
int totalNumVisualShapes = m_data->m_pluginManager.getRenderInterface()->getNumVisualShapes(bodyUniqueId);
|
||||
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
|
||||
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
|
||||
b3VisualShapeData tmpShape;
|
||||
|
||||
int remain = totalNumVisualShapes - startShapeIndex;
|
||||
int shapeIndex = startShapeIndex;
|
||||
|
||||
int success = m_data->m_pluginManager.getRenderInterface()->getVisualShapesData(bodyUniqueId,shapeIndex,&tmpShape);
|
||||
if (success)
|
||||
{
|
||||
if (tmpShape.m_tinyRendererTextureId>=0)
|
||||
{
|
||||
int openglTextureUniqueId = -1;
|
||||
|
||||
//find companion opengl texture unique id and create a 'textureUid'
|
||||
if (currentOpenGLTextureIndex<u2b.getNumAllocatedTextures())
|
||||
{
|
||||
openglTextureUniqueId = u2b.getAllocatedTexture(currentOpenGLTextureIndex);
|
||||
currentOpenGLTextureIndex++;
|
||||
}
|
||||
|
||||
int texHandle = m_data->m_textureHandles.allocHandle();
|
||||
InternalTextureHandle* texH = m_data->m_textureHandles.getHandle(texHandle);
|
||||
if(texH)
|
||||
{
|
||||
texH->m_tinyRendererTextureId = tmpShape.m_tinyRendererTextureId;
|
||||
texH->m_openglTextureId = openglTextureUniqueId;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -2895,6 +2934,14 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
int texHandle = m_data->m_textureHandles.allocHandle();
|
||||
InternalTextureHandle* texH = m_data->m_textureHandles.getHandle(texHandle);
|
||||
if(texH)
|
||||
{
|
||||
texH->m_tinyRendererTextureId = -1;
|
||||
texH->m_openglTextureId = -1;
|
||||
*/
|
||||
|
||||
for (int i=0;i<u2b.getNumAllocatedMeshInterfaces();i++)
|
||||
{
|
||||
@@ -9284,6 +9331,25 @@ bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const s
|
||||
shapeIndex,
|
||||
visualShapeStoragePtr);
|
||||
if (success) {
|
||||
|
||||
//find the matching texture unique ids.
|
||||
if (visualShapeStoragePtr->m_tinyRendererTextureId>=0)
|
||||
{
|
||||
b3AlignedObjectArray<int> usedHandles;
|
||||
m_data->m_textureHandles.getUsedHandles(usedHandles);
|
||||
|
||||
for (int i=0;i<usedHandles.size();i++)
|
||||
{
|
||||
int texHandle =usedHandles[i];
|
||||
InternalTextureHandle* texH = m_data->m_textureHandles.getHandle(texHandle);
|
||||
if (texH && (texH->m_tinyRendererTextureId == visualShapeStoragePtr->m_tinyRendererTextureId))
|
||||
{
|
||||
visualShapeStoragePtr->m_openglTextureId =texH->m_openglTextureId;
|
||||
visualShapeStoragePtr->m_textureUniqueId = texHandle;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
serverCmd.m_sendVisualShapeArgs.m_numRemainingVisualShapes = remain-1;
|
||||
serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied = 1;
|
||||
serverCmd.m_sendVisualShapeArgs.m_startingVisualShapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
|
||||
|
||||
@@ -595,6 +595,11 @@ typedef union {
|
||||
#define MAX_RAY_HITS MAX_RAY_INTERSECTION_BATCH_SIZE
|
||||
#define VISUAL_SHAPE_MAX_PATH_LEN 1024
|
||||
|
||||
enum b3VisualShapeDataFlags
|
||||
{
|
||||
eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS = 1,
|
||||
};
|
||||
|
||||
struct b3VisualShapeData
|
||||
{
|
||||
int m_objectUniqueId;
|
||||
@@ -605,6 +610,10 @@ struct b3VisualShapeData
|
||||
double m_localVisualFrame[7];//pos[3], orn[4]
|
||||
//todo: add more data if necessary (material color etc, although material can be in asset file .obj file)
|
||||
double m_rgbaColor[4];
|
||||
int m_tinyRendererTextureId;
|
||||
int m_textureUniqueId;
|
||||
int m_openglTextureId;
|
||||
|
||||
};
|
||||
|
||||
struct b3VisualShapeInformation
|
||||
|
||||
@@ -155,6 +155,69 @@ btVector3 b3RobotSimulatorClientAPI_NoDirect::getEulerFromQuaternion(const btQua
|
||||
return rpy2;
|
||||
}
|
||||
|
||||
int b3RobotSimulatorClientAPI_NoDirect::loadTexture(const std::string& fileName)
|
||||
{
|
||||
if (!isConnected())
|
||||
{
|
||||
b3Warning("Not connected");
|
||||
return -1;
|
||||
}
|
||||
btAssert(b3CanSubmitCommand(m_data->m_physicsClientHandle));
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
{
|
||||
commandHandle = b3InitLoadTexture(m_data->m_physicsClientHandle, fileName.c_str());
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_LOAD_TEXTURE_COMPLETED)
|
||||
{
|
||||
return b3GetStatusTextureUniqueId(statusHandle);
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
bool b3RobotSimulatorClientAPI_NoDirect::changeVisualShape(const struct b3RobotSimulatorChangeVisualShapeArgs& args)
|
||||
{
|
||||
if (!isConnected())
|
||||
{
|
||||
b3Warning("Not connected");
|
||||
return false;
|
||||
}
|
||||
|
||||
int objectUniqueId = args.m_objectUniqueId;
|
||||
int jointIndex = args.m_linkIndex;
|
||||
int shapeIndex = args.m_shapeIndex;
|
||||
int textureUniqueId = args.m_textureUniqueId;
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
commandHandle = b3InitUpdateVisualShape(m_data->m_physicsClientHandle, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
|
||||
|
||||
if (args.m_hasSpecularColor)
|
||||
{
|
||||
double specularColor[3] = {args.m_specularColor[0],args.m_specularColor[1],args.m_specularColor[2]};
|
||||
b3UpdateVisualShapeSpecularColor(commandHandle,specularColor);
|
||||
}
|
||||
if (args.m_hasRgbaColor)
|
||||
{
|
||||
double rgbaColor[4] = {args.m_rgbaColor[0],args.m_rgbaColor[1],args.m_rgbaColor[2],args.m_rgbaColor[3]};
|
||||
b3UpdateVisualShapeRGBAColor(commandHandle,rgbaColor);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
return (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED);
|
||||
}
|
||||
|
||||
int b3RobotSimulatorClientAPI_NoDirect::loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args)
|
||||
{
|
||||
int robotUniqueId = -1;
|
||||
@@ -2177,7 +2240,8 @@ void b3RobotSimulatorClientAPI_NoDirect::restoreStateFromMemory(int stateId)
|
||||
bool b3RobotSimulatorClientAPI_NoDirect::getVisualShapeData(int bodyUniqueId, b3VisualShapeInformation &visualShapeInfo)
|
||||
{
|
||||
b3PhysicsClientHandle sm = m_data->m_physicsClientHandle;
|
||||
if (sm == 0) {
|
||||
if (sm == 0)
|
||||
{
|
||||
b3Warning("Not connected");
|
||||
return false;
|
||||
}
|
||||
@@ -2185,17 +2249,17 @@ bool b3RobotSimulatorClientAPI_NoDirect::getVisualShapeData(int bodyUniqueId, b3
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
{
|
||||
commandHandle = b3InitRequestVisualShapeInformation(sm, bodyUniqueId);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
|
||||
btAssert(statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED);
|
||||
if (statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED) {
|
||||
if (statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED)
|
||||
{
|
||||
b3GetVisualShapeInformation(sm, &visualShapeInfo);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void b3RobotSimulatorClientAPI_NoDirect::setAdditionalSearchPath(const std::string& path)
|
||||
|
||||
@@ -60,6 +60,30 @@ struct b3RobotSimulatorLoadFileResults
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorChangeVisualShapeArgs
|
||||
{
|
||||
int m_objectUniqueId;
|
||||
int m_linkIndex;
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
btVector4 m_rgbaColor;
|
||||
bool m_hasRgbaColor;
|
||||
btVector3 m_specularColor;
|
||||
bool m_hasSpecularColor;
|
||||
|
||||
b3RobotSimulatorChangeVisualShapeArgs()
|
||||
:m_objectUniqueId(-1),
|
||||
m_linkIndex(-1),
|
||||
m_shapeIndex(-1),
|
||||
m_textureUniqueId(-1),
|
||||
m_rgbaColor(0,0,0,1),
|
||||
m_hasRgbaColor(false),
|
||||
m_specularColor(1,1,1),
|
||||
m_hasSpecularColor(false)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorJointMotorArgs
|
||||
{
|
||||
int m_controlMode;
|
||||
@@ -505,6 +529,10 @@ public:
|
||||
bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results);
|
||||
bool saveBullet(const std::string& fileName);
|
||||
|
||||
int loadTexture(const std::string& fileName);
|
||||
|
||||
bool changeVisualShape(const struct b3RobotSimulatorChangeVisualShapeArgs& args);
|
||||
|
||||
bool savePythonWorld(const std::string& fileName);
|
||||
|
||||
bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo* bodyInfo);
|
||||
@@ -648,7 +676,7 @@ public:
|
||||
|
||||
bool getCollisionShapeData(int bodyUniqueId, int linkIndex, b3CollisionShapeInformation &collisionShapeInfo);
|
||||
|
||||
bool getVisualShapeData(int bodyUniqueId, b3VisualShapeInformation &visualShapeInfo);
|
||||
bool getVisualShapeData(int bodyUniqueId, struct b3VisualShapeInformation &visualShapeInfo);
|
||||
|
||||
int saveStateToMemory();
|
||||
void restoreStateFromMemory(int stateId);
|
||||
|
||||
@@ -671,12 +671,14 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
visualShape.m_rgbaColor[1] = rgbaColor[1];
|
||||
visualShape.m_rgbaColor[2] = rgbaColor[2];
|
||||
visualShape.m_rgbaColor[3] = rgbaColor[3];
|
||||
visualShape.m_openglTextureId = -1;
|
||||
visualShape.m_tinyRendererTextureId = -1;
|
||||
visualShape.m_textureUniqueId = -1;
|
||||
|
||||
{
|
||||
B3_PROFILE("convertURDFToVisualShape");
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures, visualShape);
|
||||
}
|
||||
m_data->m_visualShapes.push_back(visualShape);
|
||||
|
||||
if (vertices.size() && indices.size())
|
||||
{
|
||||
@@ -701,13 +703,15 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
}
|
||||
visuals->m_renderObjects.push_back(tinyObj);
|
||||
}
|
||||
|
||||
btAssert(textures.size()<=1);
|
||||
for (int i=0;i<textures.size();i++)
|
||||
{
|
||||
if (!textures[i].m_isCached)
|
||||
{
|
||||
free(textures[i].textureData1);
|
||||
}
|
||||
visualShape.m_tinyRendererTextureId = m_data->m_textures.size();
|
||||
m_data->m_textures.push_back(textures[i]);
|
||||
}
|
||||
m_data->m_visualShapes.push_back(visualShape);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1199,13 +1203,13 @@ void TinyRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, in
|
||||
for (int v = 0; v < visualArray->m_renderObjects.size(); v++)
|
||||
{
|
||||
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
|
||||
|
||||
if ((shapeIndex < 0) || (shapeIndex == v))
|
||||
{
|
||||
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
19
examples/pybullet/examples/getTextureUid.py
Normal file
19
examples/pybullet/examples/getTextureUid.py
Normal file
@@ -0,0 +1,19 @@
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
plane = p.loadURDF("plane.urdf")
|
||||
visualData = p.getVisualShapeData(plane, p.VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS)
|
||||
print(visualData)
|
||||
curTexUid = visualData[0][8]
|
||||
print(curTexUid)
|
||||
texUid = p.loadTexture("tex256.png")
|
||||
print("texUid=",texUid)
|
||||
|
||||
p.changeVisualShape(plane,-1,textureUniqueId=texUid)
|
||||
|
||||
for i in range (100):
|
||||
p.getCameraImage(320,200)
|
||||
p.changeVisualShape(plane,-1,textureUniqueId=curTexUid)
|
||||
|
||||
for i in range (100):
|
||||
p.getCameraImage(320,200)
|
||||
|
||||
@@ -13,8 +13,8 @@ bearStartPos2 = [0,0,0]
|
||||
bearStartOrientation2 = p.getQuaternionFromEuler([0,0,0])
|
||||
bearId2 = p.loadURDF("teddy_large.urdf",bearStartPos2, bearStartOrientation2)
|
||||
textureId = p.loadTexture("checker_grid.jpg")
|
||||
p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
|
||||
p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
|
||||
#p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
|
||||
#p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
|
||||
|
||||
|
||||
useRealTimeSimulation = 1
|
||||
|
||||
@@ -5428,8 +5428,10 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
|
||||
PyObject* pyResultList = 0;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"objectUniqueId", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &objectUniqueId, &physicsClientId))
|
||||
int flags=0;
|
||||
|
||||
static char* kwlist[] = {"objectUniqueId", "flags", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|ii", kwlist, &objectUniqueId, &flags, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -5450,7 +5452,9 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
|
||||
pyResultList = PyTuple_New(visualShapeInfo.m_numVisualShapes);
|
||||
for (i = 0; i < visualShapeInfo.m_numVisualShapes; i++)
|
||||
{
|
||||
PyObject* visualShapeObList = PyTuple_New(8);
|
||||
int numFields = flags&eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS ? 9 : 8;
|
||||
|
||||
PyObject* visualShapeObList = PyTuple_New(numFields);
|
||||
PyObject* item;
|
||||
item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_objectUniqueId);
|
||||
PyTuple_SetItem(visualShapeObList, 0, item);
|
||||
@@ -5511,6 +5515,11 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
|
||||
PyTuple_SetItem(rgba, 3, item);
|
||||
PyTuple_SetItem(visualShapeObList, 7, rgba);
|
||||
}
|
||||
if (flags&eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS)
|
||||
{
|
||||
item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_textureUniqueId);
|
||||
PyTuple_SetItem(visualShapeObList, 8, item);
|
||||
}
|
||||
|
||||
PyTuple_SetItem(pyResultList, i, visualShapeObList);
|
||||
}
|
||||
@@ -9656,6 +9665,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS);
|
||||
|
||||
PyModule_AddIntConstant(m, "VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS", eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS);
|
||||
|
||||
PyModule_AddIntConstant(m, "MAX_RAY_INTERSECTION_BATCH_SIZE", MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING);
|
||||
|
||||
PyModule_AddIntConstant(m, "B3G_F1", B3G_F1);
|
||||
|
||||
Reference in New Issue
Block a user