mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-18 21:10:05 +00:00
Add loading texture API.
This commit is contained in:
parent
05be92d006
commit
4911b14271
@ -1252,31 +1252,38 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
||||
}
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient)
|
||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename)
|
||||
{
|
||||
/*
|
||||
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_updateFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
*/
|
||||
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_requestVisualShapeDataArguments.m_bodyUniqueId = 0;
|
||||
//command->m_requestVisualShapeDataArguments.m_startingVisualShapeIndex = 0;
|
||||
command->m_type = CMD_LOAD_TEXTURE;
|
||||
int len = strlen(filename);
|
||||
if (len<MAX_FILENAME_LENGTH)
|
||||
{
|
||||
strcpy(command->m_loadTextureArguments.m_textureFileName,filename);
|
||||
} else
|
||||
{
|
||||
command->m_loadTextureArguments.m_textureFileName[0] = 0;
|
||||
}
|
||||
command->m_updateFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, 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_textureUniqueId = textureUniqueId;
|
||||
command->m_updateFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
|
||||
|
@ -99,7 +99,8 @@ void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3Con
|
||||
b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA);
|
||||
void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient);
|
||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int textureUniqueId);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
||||
|
@ -489,7 +489,14 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
}
|
||||
case CMD_UPDATE_VISUAL_SHAPE:
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle);
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle,8,0);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
case CMD_LOAD_TEXTURE:
|
||||
{
|
||||
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);
|
||||
break;
|
||||
}
|
||||
@ -572,6 +579,7 @@ void PhysicsClientExample::createButtons()
|
||||
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
||||
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
||||
createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger);
|
||||
createButton("Load Texture",CMD_LOAD_TEXTURE, isTrigger);
|
||||
createButton("Update Visual Shape",CMD_UPDATE_VISUAL_SHAPE, isTrigger);
|
||||
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
|
||||
if (m_options!=eCLIENTEXAMPLE_SERVER)
|
||||
|
@ -666,6 +666,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
b3Warning("Visual Shape Update failed");
|
||||
break;
|
||||
}
|
||||
case CMD_LOAD_TEXTURE_COMPLETED:
|
||||
{
|
||||
break;
|
||||
}
|
||||
case CMD_LOAD_TEXTURE_FAILED:
|
||||
{
|
||||
b3Warning("Load texture failed");
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
b3Error("Unknown server status %d\n", serverCmd.m_type);
|
||||
btAssert(0);
|
||||
|
@ -3006,15 +3006,26 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_FAILED;
|
||||
|
||||
const char filename[] = "/Users/yunfeibai/Documents/dev/bullet-change-texture/bullet3/data/checker_huge.gif";
|
||||
m_data->m_visualConverter.loadTextureFile(filename);
|
||||
m_data->m_visualConverter.activateShapeTexture(0, 0);
|
||||
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
|
||||
|
||||
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
|
||||
hasStatus = true;
|
||||
|
||||
break;
|
||||
}
|
||||
case CMD_LOAD_TEXTURE:
|
||||
{
|
||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||
serverCmd.m_type = CMD_LOAD_TEXTURE_FAILED;
|
||||
|
||||
m_data->m_visualConverter.loadTextureFile(clientCmd.m_loadTextureArguments.m_textureFileName);
|
||||
|
||||
serverCmd.m_type = CMD_LOAD_TEXTURE_COMPLETED;
|
||||
hasStatus = true;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
default:
|
||||
{
|
||||
b3Error("Unknown command encountered");
|
||||
|
@ -157,6 +157,17 @@ struct RequestVisualShapeDataArgs
|
||||
int m_startingVisualShapeIndex;
|
||||
};
|
||||
|
||||
struct UpdateVisualShapeDataArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
int m_textureUniqueId;
|
||||
};
|
||||
|
||||
struct LoadTextureArgs
|
||||
{
|
||||
char m_textureFileName[MAX_FILENAME_LENGTH];
|
||||
};
|
||||
|
||||
struct SendVisualShapeDataArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
@ -477,6 +488,8 @@ struct SharedMemoryCommand
|
||||
struct CreateJointArgs m_createJointArguments;
|
||||
struct RequestContactDataArgs m_requestContactPointArguments;
|
||||
struct RequestVisualShapeDataArgs m_requestVisualShapeDataArguments;
|
||||
struct UpdateVisualShapeDataArgs m_updateVisualShapeDataArguments;
|
||||
struct LoadTextureArgs m_loadTextureArguments;
|
||||
struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments;
|
||||
};
|
||||
};
|
||||
|
@ -36,6 +36,7 @@ enum EnumSharedMemoryClientCommand
|
||||
CMD_SAVE_WORLD,
|
||||
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
||||
CMD_UPDATE_VISUAL_SHAPE,
|
||||
CMD_LOAD_TEXTURE,
|
||||
//don't go beyond this command!
|
||||
CMD_MAX_CLIENT_COMMANDS,
|
||||
|
||||
@ -84,6 +85,8 @@ enum EnumSharedMemoryServerStatus
|
||||
CMD_VISUAL_SHAPE_INFO_FAILED,
|
||||
CMD_VISUAL_SHAPE_UPDATE_COMPLETED,
|
||||
CMD_VISUAL_SHAPE_UPDATE_FAILED,
|
||||
CMD_LOAD_TEXTURE_COMPLETED,
|
||||
CMD_LOAD_TEXTURE_FAILED,
|
||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||
CMD_MAX_SERVER_COMMANDS
|
||||
};
|
||||
|
@ -70,9 +70,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
int m_swWidth;
|
||||
int m_swHeight;
|
||||
TGAImage m_rgbColorBuffer;
|
||||
unsigned char* m_texture;
|
||||
int m_textureWidth;
|
||||
int m_textureHeight;
|
||||
b3AlignedObjectArray<MyTexture2> m_textures;
|
||||
b3AlignedObjectArray<float> m_depthBuffer;
|
||||
b3AlignedObjectArray<int> m_segmentationMaskBuffer;
|
||||
|
||||
@ -832,27 +830,24 @@ void TinyRendererVisualShapeConverter::resetAll()
|
||||
m_data->m_swRenderInstances.clear();
|
||||
}
|
||||
|
||||
// Get shapeUniqueId from getVisualShapesData?
|
||||
void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, int textureUniqueId)
|
||||
{
|
||||
// Use shapeUniqueId?
|
||||
int objectArrayIndex = 8;
|
||||
int objectIndex = 0;
|
||||
printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size());
|
||||
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(objectArrayIndex);
|
||||
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(shapeUniqueId);
|
||||
if (ptrptr && *ptrptr)
|
||||
{
|
||||
TinyRendererObjectArray* ptr = *ptrptr;
|
||||
ptr->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(m_data->m_texture,m_data->m_textureWidth,m_data->m_textureHeight);
|
||||
ptr->m_renderObjects[0]->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData,m_data->m_textures[textureUniqueId].m_width,m_data->m_textures[textureUniqueId].m_height);
|
||||
}
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int width, int height)
|
||||
{
|
||||
m_data->m_texture = texels;
|
||||
m_data->m_textureWidth = width;
|
||||
m_data->m_textureHeight = height;
|
||||
return 0;
|
||||
MyTexture2 texData;
|
||||
texData.m_width = width;
|
||||
texData.m_height = height;
|
||||
texData.textureData = texels;
|
||||
m_data->m_textures.push_back(texData);
|
||||
return m_data->m_textures.size()-1;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
|
Loading…
Reference in New Issue
Block a user