PyBullet change API (since it was broken): pybullet_changeVisualShape with textureUniqueId ==-1 will clear the texture

b3InitUpdateVisualShape doesn't take textureUniqueId by default. new API b3UpdateVisualShapeTexture to change texture (-1 will clear texture)
PyBullet/BulletRobotics: allow to reset the textureUniqueId to -1, to clear a texture
PyBullet/BulletRobotics: save all texture handles
This commit is contained in:
erwincoumans
2018-10-20 15:56:56 -07:00
parent 9a9386b6a7
commit ed49edc1af
8 changed files with 90 additions and 42 deletions

View File

@@ -1009,6 +1009,10 @@ void GLInstancingRenderer::replaceTexture(int shapeIndex, int textureId)
{
gfxObj->m_textureIndex = textureId;
gfxObj->m_flags |= eGfxHasTexture;
} else
{
gfxObj->m_textureIndex = -1;
gfxObj->m_flags &= ~eGfxHasTexture;
}
}
}

View File

@@ -4008,7 +4008,7 @@ B3_SHARED_API int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHa
return uid;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
@@ -4019,14 +4019,25 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClien
command->m_updateVisualShapeDataArguments.m_bodyUniqueId = bodyUniqueId;
command->m_updateVisualShapeDataArguments.m_jointIndex = jointIndex;
command->m_updateVisualShapeDataArguments.m_shapeIndex = shapeIndex;
command->m_updateVisualShapeDataArguments.m_textureUniqueId = textureUniqueId;
command->m_updateVisualShapeDataArguments.m_textureUniqueId = -2;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
if (textureUniqueId >= 0)
B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_UPDATE_VISUAL_SHAPE);
if (command->m_type == CMD_UPDATE_VISUAL_SHAPE)
{
if (textureUniqueId >= -1)
{
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_TEXTURE;
command->m_updateVisualShapeDataArguments.m_textureUniqueId = textureUniqueId;
}
}
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[4])

View File

@@ -308,7 +308,8 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateChangeTextureCommandInit(b3PhysicsClientHandle physClient, int textureUniqueId, int width, int height, const char* rgbPixels);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex);
B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId);
B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[/*4*/]);
B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[/*3*/]);

View File

@@ -2755,7 +2755,7 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
SaveWorldObjectData sd;
sd.m_fileName = fileName;
int currentOpenGLTextureIndex = 0;
for (int m = 0; m < u2b.getNumModels(); m++)
{
@@ -2971,18 +2971,16 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
}
{
int startShapeIndex = 0;
if (m_data->m_pluginManager.getRenderInterface())
{
int currentOpenGLTextureIndex=0;
int totalNumVisualShapes = m_data->m_pluginManager.getRenderInterface()->getNumVisualShapes(bodyUniqueId);
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
for (int shapeIndex=0;shapeIndex<totalNumVisualShapes;shapeIndex++)
{
b3VisualShapeData tmpShape;
int remain = totalNumVisualShapes - startShapeIndex;
int shapeIndex = startShapeIndex;
int success = m_data->m_pluginManager.getRenderInterface()->getVisualShapesData(bodyUniqueId, shapeIndex, &tmpShape);
if (success)
{
@@ -2991,12 +2989,12 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
int openglTextureUniqueId = -1;
//find companion opengl texture unique id and create a 'textureUid'
if (currentOpenGLTextureIndex < u2b.getNumAllocatedTextures())
if (currentOpenGLTextureIndex<u2b.getNumAllocatedTextures())
{
openglTextureUniqueId = u2b.getAllocatedTexture(currentOpenGLTextureIndex);
currentOpenGLTextureIndex++;
openglTextureUniqueId = u2b.getAllocatedTexture(currentOpenGLTextureIndex++);
}
//if (openglTextureUniqueId>=0)
{
int texHandle = m_data->m_textureHandles.allocHandle();
InternalTextureHandle* texH = m_data->m_textureHandles.getHandle(texHandle);
if (texH)
@@ -3008,6 +3006,8 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
}
}
}
}
}
b3Notification notification;
notification.m_notificationType = BODY_ADDED;
@@ -9778,10 +9778,13 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
InternalTextureHandle* texHandle = 0;
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_TEXTURE)
{
if (clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId>=0)
{
texHandle = m_data->m_textureHandles.getHandle(clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
}
if (clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId >= 0)
if (clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId >= -1)
{
if (texHandle)
{
@@ -9792,6 +9795,12 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex,
texHandle->m_tinyRendererTextureId);
}
} else
{
m_data->m_pluginManager.getRenderInterface()->changeShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId,
clientCmd.m_updateVisualShapeDataArguments.m_jointIndex,
clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex,
-1);
}
}
}
@@ -9812,10 +9821,13 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_TEXTURE)
{
int shapeIndex = m_data->m_guiHelper->getShapeIndexFromInstance(graphicsIndex);
if (texHandle)
{
int shapeIndex = m_data->m_guiHelper->getShapeIndexFromInstance(graphicsIndex);
m_data->m_guiHelper->replaceTexture(shapeIndex, texHandle->m_openglTextureId);
} else
{
m_data->m_guiHelper->replaceTexture(shapeIndex, -1);
}
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
@@ -9843,11 +9855,15 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_TEXTURE)
{
int shapeIndex = m_data->m_guiHelper->getShapeIndexFromInstance(graphicsIndex);
if (texHandle)
{
int shapeIndex = m_data->m_guiHelper->getShapeIndexFromInstance(graphicsIndex);
m_data->m_guiHelper->replaceTexture(shapeIndex, texHandle->m_openglTextureId);
}
else
{
m_data->m_guiHelper->replaceTexture(shapeIndex, -1);
}
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
{

View File

@@ -190,7 +190,12 @@ bool b3RobotSimulatorClientAPI_NoDirect::changeVisualShape(const struct b3RobotS
b3SharedMemoryStatusHandle statusHandle;
int statusType;
commandHandle = b3InitUpdateVisualShape(m_data->m_physicsClientHandle, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
commandHandle = b3InitUpdateVisualShape(m_data->m_physicsClientHandle, objectUniqueId, jointIndex, shapeIndex);
if (textureUniqueId>=-1)
{
b3UpdateVisualShapeTexture(commandHandle, textureUniqueId);
}
if (args.m_hasSpecularColor)
{

View File

@@ -75,7 +75,7 @@ struct b3RobotSimulatorChangeVisualShapeArgs
: m_objectUniqueId(-1),
m_linkIndex(-1),
m_shapeIndex(-1),
m_textureUniqueId(-1),
m_textureUniqueId(-2),
m_rgbaColor(0, 0, 0, 1),
m_hasRgbaColor(false),
m_specularColor(1, 1, 1),

View File

@@ -1159,7 +1159,7 @@ void TinyRendererVisualShapeConverter::resetAll()
void TinyRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
{
btAssert(textureUniqueId < m_data->m_textures.size());
if (textureUniqueId >= 0 && textureUniqueId < m_data->m_textures.size())
if (textureUniqueId >= -1 && textureUniqueId < m_data->m_textures.size())
{
for (int n = 0; n < m_data->m_swRenderInstances.size(); n++)
{
@@ -1175,8 +1175,14 @@ void TinyRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, in
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
if ((shapeIndex < 0) || (shapeIndex == v))
{
if (textureUniqueId>=0)
{
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
} else
{
renderObj->m_model->setDiffuseTextureFromData(0,0,0);
}
}
}
}

View File

@@ -5584,7 +5584,7 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
int objectUniqueId = -1;
int jointIndex = -1;
int shapeIndex = -1;
int textureUniqueId = -1;
int textureUniqueId = -2;
b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
@@ -5606,7 +5606,12 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
}
{
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex);
if (textureUniqueId>=-1)
{
b3UpdateVisualShapeTexture(commandHandle, textureUniqueId);
}
if (specularColorObj)
{