Add programmatic render API and a basic test.
This commit is contained in:
@@ -1252,7 +1252,32 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient)
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
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_updateFlags = 0;
|
||||||
|
return (b3SharedMemoryCommandHandle) command;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
|
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -99,6 +99,7 @@ void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3Con
|
|||||||
b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA);
|
b3SharedMemoryCommandHandle b3InitRequestVisualShapeInformation(b3PhysicsClientHandle physClient, int bodyUniqueIdA);
|
||||||
void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo);
|
void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3VisualShapeInformation* visualShapeInfo);
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient);
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||||
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
||||||
|
|||||||
@@ -481,6 +481,12 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case CMD_UPDATE_VISUAL_SHAPE:
|
||||||
|
{
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle);
|
||||||
|
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||||
|
break;
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
b3Error("Unknown buttonId");
|
b3Error("Unknown buttonId");
|
||||||
@@ -560,6 +566,7 @@ void PhysicsClientExample::createButtons()
|
|||||||
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
||||||
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
||||||
createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger);
|
createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger);
|
||||||
|
createButton("Update Visual Shape",CMD_UPDATE_VISUAL_SHAPE, isTrigger);
|
||||||
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
|
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
|
||||||
if (m_options!=eCLIENTEXAMPLE_SERVER)
|
if (m_options!=eCLIENTEXAMPLE_SERVER)
|
||||||
{
|
{
|
||||||
@@ -997,14 +1004,20 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
|||||||
{
|
{
|
||||||
b3Warning("Cannot get visual shape information");
|
b3Warning("Cannot get visual shape information");
|
||||||
}
|
}
|
||||||
|
if (statusType == CMD_VISUAL_SHAPE_UPDATE_FAILED)
|
||||||
|
{
|
||||||
|
b3Warning("Cannot update visual shape");
|
||||||
|
}
|
||||||
if (statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED)
|
if (statusType == CMD_VISUAL_SHAPE_INFO_COMPLETED)
|
||||||
{
|
{
|
||||||
b3VisualShapeInformation shapeInfo;
|
b3VisualShapeInformation shapeInfo;
|
||||||
b3GetVisualShapeInformation(m_physicsClientHandle, &shapeInfo);
|
b3GetVisualShapeInformation(m_physicsClientHandle, &shapeInfo);
|
||||||
b3Printf("Num visual shapes: %d", shapeInfo.m_numVisualShapes);
|
b3Printf("Num visual shapes: %d", shapeInfo.m_numVisualShapes);
|
||||||
}
|
}
|
||||||
|
if (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED)
|
||||||
|
{
|
||||||
|
b3Printf("Visual shape update completed.");
|
||||||
|
}
|
||||||
if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED)
|
if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED)
|
||||||
{
|
{
|
||||||
b3ContactInformation contactPointData;
|
b3ContactInformation contactPointData;
|
||||||
|
|||||||
@@ -657,6 +657,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
|||||||
b3Warning("Visual Shape Info Request failed");
|
b3Warning("Visual Shape Info Request failed");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case CMD_VISUAL_SHAPE_UPDATE_COMPLETED:
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case CMD_VISUAL_SHAPE_UPDATE_FAILED:
|
||||||
|
{
|
||||||
|
b3Warning("Visual Shape Update failed");
|
||||||
|
break;
|
||||||
|
}
|
||||||
default: {
|
default: {
|
||||||
b3Error("Unknown server status %d\n", serverCmd.m_type);
|
b3Error("Unknown server status %d\n", serverCmd.m_type);
|
||||||
btAssert(0);
|
btAssert(0);
|
||||||
|
|||||||
@@ -3001,6 +3001,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
hasStatus = true;
|
hasStatus = true;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case CMD_UPDATE_VISUAL_SHAPE:
|
||||||
|
{
|
||||||
|
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||||
|
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_FAILED;
|
||||||
|
|
||||||
|
m_data->m_visualConverter.activateShapeTexture(0, 0);
|
||||||
|
|
||||||
|
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
|
||||||
|
hasStatus = true;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
b3Error("Unknown command encountered");
|
b3Error("Unknown command encountered");
|
||||||
|
|||||||
@@ -35,6 +35,7 @@ enum EnumSharedMemoryClientCommand
|
|||||||
CMD_REQUEST_CONTACT_POINT_INFORMATION,
|
CMD_REQUEST_CONTACT_POINT_INFORMATION,
|
||||||
CMD_SAVE_WORLD,
|
CMD_SAVE_WORLD,
|
||||||
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
||||||
|
CMD_UPDATE_VISUAL_SHAPE,
|
||||||
//don't go beyond this command!
|
//don't go beyond this command!
|
||||||
CMD_MAX_CLIENT_COMMANDS,
|
CMD_MAX_CLIENT_COMMANDS,
|
||||||
|
|
||||||
@@ -81,6 +82,8 @@ enum EnumSharedMemoryServerStatus
|
|||||||
CMD_SAVE_WORLD_FAILED,
|
CMD_SAVE_WORLD_FAILED,
|
||||||
CMD_VISUAL_SHAPE_INFO_COMPLETED,
|
CMD_VISUAL_SHAPE_INFO_COMPLETED,
|
||||||
CMD_VISUAL_SHAPE_INFO_FAILED,
|
CMD_VISUAL_SHAPE_INFO_FAILED,
|
||||||
|
CMD_VISUAL_SHAPE_UPDATE_COMPLETED,
|
||||||
|
CMD_VISUAL_SHAPE_UPDATE_FAILED,
|
||||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||||
CMD_MAX_SERVER_COMMANDS
|
CMD_MAX_SERVER_COMMANDS
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -33,6 +33,7 @@ subject to the following restrictions:
|
|||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include "../Importers/ImportURDFDemo/UrdfParser.h"
|
#include "../Importers/ImportURDFDemo/UrdfParser.h"
|
||||||
#include "../SharedMemory/SharedMemoryPublic.h"//for b3VisualShapeData
|
#include "../SharedMemory/SharedMemoryPublic.h"//for b3VisualShapeData
|
||||||
|
#include "../TinyRenderer/model.h"
|
||||||
|
|
||||||
|
|
||||||
enum MyFileType
|
enum MyFileType
|
||||||
@@ -68,6 +69,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
int m_swWidth;
|
int m_swWidth;
|
||||||
int m_swHeight;
|
int m_swHeight;
|
||||||
TGAImage m_rgbColorBuffer;
|
TGAImage m_rgbColorBuffer;
|
||||||
|
TGAImage m_texture;
|
||||||
b3AlignedObjectArray<float> m_depthBuffer;
|
b3AlignedObjectArray<float> m_depthBuffer;
|
||||||
b3AlignedObjectArray<int> m_segmentationMaskBuffer;
|
b3AlignedObjectArray<int> m_segmentationMaskBuffer;
|
||||||
|
|
||||||
@@ -77,7 +79,8 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
:m_upAxis(2),
|
:m_upAxis(2),
|
||||||
m_swWidth(START_WIDTH),
|
m_swWidth(START_WIDTH),
|
||||||
m_swHeight(START_HEIGHT),
|
m_swHeight(START_HEIGHT),
|
||||||
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB)
|
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB),
|
||||||
|
m_texture(START_WIDTH,START_HEIGHT,TGAImage::RGB)
|
||||||
{
|
{
|
||||||
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
||||||
m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1);
|
m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1);
|
||||||
@@ -827,3 +830,34 @@ void TinyRendererVisualShapeConverter::resetAll()
|
|||||||
m_data->m_swRenderInstances.clear();
|
m_data->m_swRenderInstances.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Get shapeUniqueId from getVisualShapesData?
|
||||||
|
void TinyRendererVisualShapeConverter::activateShapeTexture(int shapeUniqueId, int textureUniqueId)
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
// Use shapeUniqueId?
|
||||||
|
int objectArrayIndex = 0;
|
||||||
|
int objectIndex = 0;
|
||||||
|
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(objectArrayIndex);
|
||||||
|
TinyRendererObjectArray* visualArray = *visualArrayPtr;
|
||||||
|
unsigned char textureImage[3] = {10, 10, 255};
|
||||||
|
int textureWidth = 1000;
|
||||||
|
int textureHeight = 1000;
|
||||||
|
visualArray->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight);
|
||||||
|
*/
|
||||||
|
|
||||||
|
int objectArrayIndex = 0;
|
||||||
|
int objectIndex = 0;
|
||||||
|
for (int i=0;i<m_data->m_swRenderInstances.size();i++)
|
||||||
|
{
|
||||||
|
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances.getAtIndex(i);
|
||||||
|
if (ptrptr && *ptrptr)
|
||||||
|
{
|
||||||
|
TinyRendererObjectArray* ptr = *ptrptr;
|
||||||
|
unsigned char textureImage[3] = {255, 10, 10};
|
||||||
|
int textureWidth = 1000;
|
||||||
|
int textureHeight = 1000;
|
||||||
|
ptr->m_renderObjects[objectIndex]->m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|||||||
@@ -37,6 +37,10 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
|||||||
|
|
||||||
void render();
|
void render();
|
||||||
void render(const float viewMat[16], const float projMat[16]);
|
void render(const float viewMat[16], const float projMat[16]);
|
||||||
|
|
||||||
|
int registerTexture(unsigned char* texels, int width, int height);
|
||||||
|
void activateShapeTexture(int shapeUniqueId, int textureUniqueId);
|
||||||
|
void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -57,9 +57,12 @@ void Model::setDiffuseTextureFromData(unsigned char* textureImage,int textureWid
|
|||||||
for (int j=0;j<textureHeight;j++)
|
for (int j=0;j<textureHeight;j++)
|
||||||
{
|
{
|
||||||
TGAColor color;
|
TGAColor color;
|
||||||
color.bgra[0] = textureImage[(i+j*textureWidth)*3+0];
|
//color.bgra[0] = textureImage[(i+j*textureWidth)*3+0];
|
||||||
color.bgra[1] = textureImage[(i+j*textureWidth)*3+1];
|
//color.bgra[1] = textureImage[(i+j*textureWidth)*3+1];
|
||||||
color.bgra[2] = textureImage[(i+j*textureWidth)*3+2];
|
//color.bgra[2] = textureImage[(i+j*textureWidth)*3+2];
|
||||||
|
color.bgra[0] = textureImage[0];
|
||||||
|
color.bgra[1] = textureImage[1];
|
||||||
|
color.bgra[2] = textureImage[2];
|
||||||
color.bgra[3] = 255;
|
color.bgra[3] = 255;
|
||||||
|
|
||||||
color.bytespp = 3;
|
color.bytespp = 3;
|
||||||
|
|||||||
Reference in New Issue
Block a user