revert backward compabitility in API
This commit is contained in:
@@ -4008,7 +4008,28 @@ B3_SHARED_API int b3GetStatusTextureUniqueId(b3SharedMemoryStatusHandle statusHa
|
|||||||
return uid;
|
return uid;
|
||||||
}
|
}
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex)
|
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
|
||||||
|
{
|
||||||
|
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||||
|
b3Assert(cl);
|
||||||
|
b3Assert(cl->canSubmitCommand());
|
||||||
|
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||||
|
b3Assert(command);
|
||||||
|
command->m_type = CMD_UPDATE_VISUAL_SHAPE;
|
||||||
|
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_updateFlags = 0;
|
||||||
|
|
||||||
|
if (textureUniqueId >= 0)
|
||||||
|
{
|
||||||
|
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_TEXTURE;
|
||||||
|
}
|
||||||
|
return (b3SharedMemoryCommandHandle)command;
|
||||||
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape2(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex)
|
||||||
{
|
{
|
||||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||||
b3Assert(cl);
|
b3Assert(cl);
|
||||||
|
|||||||
@@ -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 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);
|
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||||
|
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUpdateVisualShape2(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex);
|
||||||
B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId);
|
B3_SHARED_API void b3UpdateVisualShapeTexture(b3SharedMemoryCommandHandle commandHandle, int textureUniqueId);
|
||||||
B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[/*4*/]);
|
B3_SHARED_API void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, const double rgbaColor[/*4*/]);
|
||||||
B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[/*3*/]);
|
B3_SHARED_API void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, const double specularColor[/*3*/]);
|
||||||
|
|||||||
@@ -497,7 +497,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
int shapeIndex = -1;
|
int shapeIndex = -1;
|
||||||
int textureIndex = -2;
|
int textureIndex = -2;
|
||||||
double rgbaColor[4] = {0.0, 1.0, 0.0, 1.0};
|
double rgbaColor[4] = {0.0, 1.0, 0.0, 1.0};
|
||||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle, objectUniqueId, linkIndex, shapeIndex);
|
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape2(m_physicsClientHandle, objectUniqueId, linkIndex, shapeIndex);
|
||||||
b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor);
|
b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor);
|
||||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||||
break;
|
break;
|
||||||
|
|||||||
@@ -190,7 +190,7 @@ bool b3RobotSimulatorClientAPI_NoDirect::changeVisualShape(const struct b3RobotS
|
|||||||
b3SharedMemoryStatusHandle statusHandle;
|
b3SharedMemoryStatusHandle statusHandle;
|
||||||
int statusType;
|
int statusType;
|
||||||
|
|
||||||
commandHandle = b3InitUpdateVisualShape(m_data->m_physicsClientHandle, objectUniqueId, jointIndex, shapeIndex);
|
commandHandle = b3InitUpdateVisualShape2(m_data->m_physicsClientHandle, objectUniqueId, jointIndex, shapeIndex);
|
||||||
|
|
||||||
if (textureUniqueId>=-1)
|
if (textureUniqueId>=-1)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -5606,7 +5606,7 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
|
|||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex);
|
commandHandle = b3InitUpdateVisualShape2(sm, objectUniqueId, jointIndex, shapeIndex);
|
||||||
|
|
||||||
if (textureUniqueId>=-1)
|
if (textureUniqueId>=-1)
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user