Add API to change texture with object id and link index.
This commit is contained in:
@@ -1272,7 +1272,7 @@ b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient,
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int textureUniqueId)
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
b3Assert(cl);
|
||||
@@ -1281,6 +1281,8 @@ b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physCl
|
||||
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;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
|
||||
@@ -100,7 +100,7 @@ b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientH
|
||||
void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int textureUniqueId);
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
||||
|
||||
@@ -25,6 +25,9 @@ struct MyMotorInfo2
|
||||
int camVisualizerWidth = 320;//1024/3;
|
||||
int camVisualizerHeight = 240;//768/3;
|
||||
|
||||
int loadTextureCount = 0;
|
||||
int setTextureCount = 0;
|
||||
|
||||
enum CustomCommands
|
||||
{
|
||||
CMD_CUSTOM_SET_REALTIME_SIMULATION = CMD_MAX_CLIENT_COMMANDS+1,
|
||||
@@ -242,7 +245,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
{
|
||||
case CMD_LOAD_URDF:
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model_white.urdf");
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf");
|
||||
//setting the initial position, orientation and other arguments are optional
|
||||
double startPosX = 0;
|
||||
static double startPosY = 0;
|
||||
@@ -260,9 +263,9 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf");//kuka_iiwa/model.sdf");
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
*/
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "sphere_big.urdf");
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "table/table.urdf");
|
||||
//setting the initial position, orientation and other arguments are optional
|
||||
b3LoadUrdfCommandSetStartPosition(commandHandle,0.5,0.5,0.5);
|
||||
b3LoadUrdfCommandSetStartPosition(commandHandle,2.0,2.0,0.5);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
@@ -489,15 +492,36 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
}
|
||||
case CMD_UPDATE_VISUAL_SHAPE:
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle,8,0);
|
||||
if (setTextureCount == 0)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle,1,0,0,0);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
}
|
||||
else if (setTextureCount == 1)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle,1,0,0,1);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
}
|
||||
setTextureCount++;
|
||||
if (setTextureCount >=2)
|
||||
setTextureCount = 0;
|
||||
break;
|
||||
}
|
||||
case CMD_LOAD_TEXTURE:
|
||||
{
|
||||
if (loadTextureCount == 0)
|
||||
{
|
||||
const char filename[] = "/Users/yunfeibai/Documents/dev/bullet-change-texture/bullet3/data/cube.png";
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitLoadTexture(m_physicsClientHandle, filename);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
}
|
||||
else if (loadTextureCount ==1)
|
||||
{
|
||||
const char filename[] = "/Users/yunfeibai/Documents/dev/bullet-change-texture/bullet3/data/checker_huge.gif";
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitLoadTexture(m_physicsClientHandle, filename);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
}
|
||||
loadTextureCount++;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
|
||||
@@ -3006,7 +3006,7 @@ 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_textureUniqueId);
|
||||
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;
|
||||
hasStatus = true;
|
||||
|
||||
@@ -160,6 +160,8 @@ struct RequestVisualShapeDataArgs
|
||||
struct UpdateVisualShapeDataArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
int m_jointIndex;
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
};
|
||||
|
||||
|
||||
@@ -832,6 +832,7 @@ void TinyRendererVisualShapeConverter::resetAll()
|
||||
|
||||
void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, int textureUniqueId)
|
||||
{
|
||||
btAssert(textureUniqueId < m_data->m_textures.size());
|
||||
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(shapeUniqueId);
|
||||
if (ptrptr && *ptrptr)
|
||||
{
|
||||
@@ -840,6 +841,29 @@ void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, i
|
||||
}
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
|
||||
{
|
||||
int start = -1;
|
||||
//find first one, then count how many
|
||||
for (int i = 0; i < m_data->m_visualShapes.size(); i++)
|
||||
{
|
||||
printf("object id: %d\n", m_data->m_visualShapes[i].m_objectUniqueId);
|
||||
if (m_data->m_visualShapes[i].m_objectUniqueId == objectUniqueId && m_data->m_visualShapes[i].m_linkIndex == jointIndex)
|
||||
{
|
||||
start = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (start >= 0)
|
||||
{
|
||||
if (start + shapeIndex < m_data->m_visualShapes.size())
|
||||
{
|
||||
activateShapeTexture(start + shapeIndex, textureUniqueId);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int width, int height)
|
||||
{
|
||||
MyTexture2 texData;
|
||||
|
||||
Reference in New Issue
Block a user