mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 13:50:04 +00:00
expose the changeVisualShape RGBA color for TinyRenderer, OpenGL3 renderer.
This commit is contained in:
parent
7cb763e4c8
commit
f80838e989
@ -38,7 +38,8 @@ struct GUIHelperInterface
|
||||
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) =0;
|
||||
virtual void removeAllGraphicsInstances()=0;
|
||||
virtual void removeGraphicsInstance(int graphicsUid) {}
|
||||
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
|
||||
|
||||
virtual Common2dCanvasInterface* get2dCanvasInterface()=0;
|
||||
|
||||
virtual CommonParameterInterface* getParameterInterface()=0;
|
||||
@ -125,6 +126,7 @@ struct DummyGUIHelper : public GUIHelperInterface
|
||||
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) {return -1;}
|
||||
virtual void removeAllGraphicsInstances(){}
|
||||
virtual void removeGraphicsInstance(int graphicsUid){}
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
|
||||
|
||||
virtual Common2dCanvasInterface* get2dCanvasInterface()
|
||||
{
|
||||
|
@ -55,10 +55,10 @@ struct CommonRenderInterface
|
||||
|
||||
virtual void writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex)=0;
|
||||
|
||||
virtual int getTotalNumInstances() const = 0;
|
||||
|
||||
|
@ -314,6 +314,14 @@ void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid)
|
||||
};
|
||||
}
|
||||
|
||||
void OpenGLGuiHelper::changeRGBAColor(int instanceUid, const double rgbaColor[4])
|
||||
{
|
||||
if (instanceUid>=0)
|
||||
{
|
||||
m_data->m_glApp->m_renderer->writeSingleInstanceColorToCPU(rgbaColor,instanceUid);
|
||||
};
|
||||
}
|
||||
|
||||
int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue)
|
||||
{
|
||||
int texWidth=1024;
|
||||
|
@ -26,7 +26,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling);
|
||||
virtual void removeAllGraphicsInstances();
|
||||
virtual void removeGraphicsInstance(int graphicsUid);
|
||||
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]);
|
||||
|
||||
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);
|
||||
|
||||
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld);
|
||||
|
@ -375,7 +375,7 @@ void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int bodyUniqueId,
|
||||
orientation[2] = m_data->m_instance_quaternion_ptr[srcIndex*4+2];
|
||||
orientation[3] = m_data->m_instance_quaternion_ptr[srcIndex*4+3];
|
||||
}
|
||||
void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int bodyUniqueId)
|
||||
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const double* color, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
@ -387,7 +387,7 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int body
|
||||
m_data->m_instance_colors_ptr[srcIndex*4+3]=float(color[3]);
|
||||
}
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceColorToCPU(float* color, int bodyUniqueId)
|
||||
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const float* color, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
@ -399,7 +399,7 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(float* color, int bodyU
|
||||
m_data->m_instance_colors_ptr[srcIndex*4+3]=color[3];
|
||||
}
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(float* scale, int bodyUniqueId)
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
@ -410,7 +410,7 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(float* scale, int bodyU
|
||||
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
|
||||
}
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(double* scale, int bodyUniqueId)
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
|
@ -98,11 +98,11 @@ public:
|
||||
|
||||
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
|
||||
|
||||
virtual struct GLInstanceRendererInternalData* getInternalData();
|
||||
|
@ -139,18 +139,18 @@ void SimpleOpenGL2Renderer::removeGraphicsInstance(int instanceUid)
|
||||
m_data->m_graphicsInstancesPool.freeHandle(instanceUid);
|
||||
}
|
||||
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(float* color, int srcIndex)
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const float* color, int srcIndex)
|
||||
{
|
||||
}
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(double* color, int srcIndex)
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const double* color, int srcIndex)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(float* scale, int srcIndex)
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const float* scale, int srcIndex)
|
||||
{
|
||||
}
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(double* scale, int srcIndex)
|
||||
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const double* scale, int srcIndex)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -34,10 +34,10 @@ public:
|
||||
virtual void removeAllInstances();
|
||||
virtual void removeGraphicsInstance(int instanceUid);
|
||||
|
||||
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
virtual void getCameraViewMatrix(float viewMat[16]) const;
|
||||
virtual void getCameraProjectionMatrix(float projMat[16]) const;
|
||||
|
||||
|
@ -2320,9 +2320,30 @@ b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physCl
|
||||
command->m_updateVisualShapeDataArguments.m_shapeIndex = shapeIndex;
|
||||
command->m_updateVisualShapeDataArguments.m_textureUniqueId = textureUniqueId;
|
||||
command->m_updateFlags = 0;
|
||||
|
||||
if (textureUniqueId>=0)
|
||||
{
|
||||
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_TEXTURE;
|
||||
}
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_UPDATE_VISUAL_SHAPE);
|
||||
|
||||
if (command->m_type == CMD_UPDATE_VISUAL_SHAPE)
|
||||
{
|
||||
command->m_updateVisualShapeDataArguments.m_rgbaColor[0] = rgbaColor[0];
|
||||
command->m_updateVisualShapeDataArguments.m_rgbaColor[1] = rgbaColor[1];
|
||||
command->m_updateVisualShapeDataArguments.m_rgbaColor[2] = rgbaColor[2];
|
||||
command->m_updateVisualShapeDataArguments.m_rgbaColor[3] = rgbaColor[3];
|
||||
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR;
|
||||
}
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
@ -198,6 +198,7 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
||||
|
@ -5585,9 +5585,52 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_FAILED;
|
||||
|
||||
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
|
||||
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_TEXTURE)
|
||||
{
|
||||
if (clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId>=0)
|
||||
{
|
||||
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
int bodyUniqueId = clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId;
|
||||
int linkIndex = clientCmd.m_updateVisualShapeDataArguments.m_jointIndex;
|
||||
|
||||
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId);
|
||||
if (bodyHandle)
|
||||
{
|
||||
if (bodyHandle->m_multiBody)
|
||||
{
|
||||
if (linkIndex==-1)
|
||||
{
|
||||
if (bodyHandle->m_multiBody->getBaseCollider())
|
||||
{
|
||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
} else
|
||||
{
|
||||
if (linkIndex<bodyHandle->m_multiBody->getNumLinks())
|
||||
{
|
||||
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
|
||||
{
|
||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
}
|
||||
}
|
||||
} else
|
||||
{
|
||||
//todo: change color for rigid body
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
|
||||
hasStatus = true;
|
||||
|
||||
break;
|
||||
|
@ -180,6 +180,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
||||
eGUIUserDebugRemoveAllItems,
|
||||
eGUIDumpFramesToVideo,
|
||||
eGUIHelperRemoveGraphicsInstance,
|
||||
eGUIHelperChangeGraphicsInstanceRGBAColor,
|
||||
};
|
||||
|
||||
|
||||
@ -788,6 +789,20 @@ public:
|
||||
workerThreadWait();
|
||||
}
|
||||
|
||||
double m_rgbaColor[4];
|
||||
int m_graphicsInstanceChangeColor;
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4])
|
||||
{
|
||||
m_graphicsInstanceChangeColor = instanceUid;
|
||||
m_rgbaColor[0] = rgbaColor[0];
|
||||
m_rgbaColor[1] = rgbaColor[1];
|
||||
m_rgbaColor[2] = rgbaColor[2];
|
||||
m_rgbaColor[3] = rgbaColor[3];
|
||||
m_cs->lock();
|
||||
m_cs->setSharedParam(1,eGUIHelperChangeGraphicsInstanceRGBAColor);
|
||||
workerThreadWait();
|
||||
}
|
||||
|
||||
virtual Common2dCanvasInterface* get2dCanvasInterface()
|
||||
{
|
||||
return 0;
|
||||
@ -1573,8 +1588,13 @@ void PhysicsServerExample::updateGraphics()
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
|
||||
case eGUIHelperChangeGraphicsInstanceRGBAColor:
|
||||
{
|
||||
m_multiThreadedHelper->m_childGuiHelper->changeRGBAColor(m_multiThreadedHelper->m_graphicsInstanceChangeColor,m_multiThreadedHelper->m_rgbaColor);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
|
||||
case eGUIHelperCopyCameraImageData:
|
||||
{
|
||||
|
@ -245,12 +245,19 @@ struct RequestVisualShapeDataArgs
|
||||
int m_startingVisualShapeIndex;
|
||||
};
|
||||
|
||||
enum EnumUpdateVisualShapeData
|
||||
{
|
||||
CMD_UPDATE_VISUAL_SHAPE_TEXTURE=1,
|
||||
CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR=2,
|
||||
};
|
||||
|
||||
struct UpdateVisualShapeDataArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
int m_jointIndex;
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
double m_rgbaColor[4];
|
||||
};
|
||||
|
||||
struct LoadTextureArgs
|
||||
|
@ -4027,7 +4027,7 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int objectUniqueId = -1;
|
||||
int jointIndex = -1;
|
||||
@ -4037,9 +4037,11 @@ static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, P
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int physicsClientId = 0;
|
||||
PyObject* rgbaColorObj = 0;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"objectUniqueId", "jointIndex", "shapeIndex", "textureUniqueId", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiii|i", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &physicsClientId))
|
||||
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOi", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@ -4052,6 +4054,14 @@ static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, P
|
||||
|
||||
{
|
||||
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
|
||||
|
||||
if (rgbaColorObj)
|
||||
{
|
||||
double rgbaColor[4] = {1,1,1,1};
|
||||
pybullet_internalSetVector4d(rgbaColorObj, rgbaColor);
|
||||
b3UpdateVisualShapeRGBAColor(commandHandle,rgbaColor);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED)
|
||||
@ -5913,7 +5923,7 @@ static PyMethodDef SpamMethods[] = {
|
||||
"Reset the state (position, velocity etc) for a joint on a body "
|
||||
"instantaneously, not through physics simulation."},
|
||||
|
||||
{"changeDynamicsInfo", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
{"changeDynamics", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"change dynamics information such as mass, lateral friction coefficient."},
|
||||
|
||||
{"getDynamicsInfo", (PyCFunction)pybullet_getDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
@ -6019,8 +6029,11 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS | METH_KEYWORDS,
|
||||
"Return the visual shape information for one object."},
|
||||
|
||||
{"resetVisualShapeData", (PyCFunction)pybullet_resetVisualShapeData, METH_VARARGS | METH_KEYWORDS,
|
||||
"Reset part of the visual shape information for one object."},
|
||||
{"changeVisualShape", (PyCFunction)pybullet_changeVisualShape, METH_VARARGS | METH_KEYWORDS,
|
||||
"Change part of the visual shape information for one object."},
|
||||
|
||||
{"resetVisualShapeData", (PyCFunction)pybullet_changeVisualShape, METH_VARARGS | METH_KEYWORDS,
|
||||
"Obsolete method, kept for backward compatibility, use changeVisualShapeData instead."},
|
||||
|
||||
{"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS,
|
||||
"Load texture file."},
|
||||
|
Loading…
Reference in New Issue
Block a user