mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Merge pull request #646 from erwincoumans/master
initial hookup of TinyRenderer to shared memory interface
This commit is contained in:
commit
68932b0c0a
@ -328,8 +328,8 @@ void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float c
|
||||
|
||||
void OpenGLGuiHelper::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
||||
{
|
||||
int w = m_data->m_glApp->m_window->getWidth();
|
||||
int h = m_data->m_glApp->m_window->getHeight();
|
||||
int w = m_data->m_glApp->m_window->getWidth()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
int h = m_data->m_glApp->m_window->getHeight()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
|
||||
if (widthPtr)
|
||||
*widthPtr = w;
|
||||
|
@ -659,6 +659,7 @@ SimpleOpenGL3App::~SimpleOpenGL3App()
|
||||
|
||||
void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes)
|
||||
{
|
||||
|
||||
int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth();
|
||||
int height = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenHeight();
|
||||
if ((width*height*4) == bufferSizeInBytes)
|
||||
|
@ -176,7 +176,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
|
||||
float orn[4]={0,0,0,1};
|
||||
float color[4]={1,1,1,1};
|
||||
float scaling[4]={1,1,1,1};
|
||||
|
||||
|
||||
m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
m_guiHelper->getRenderInterface()->writeTransforms();
|
||||
|
||||
@ -189,7 +189,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
|
||||
ob->registerMeshShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
|
||||
meshData.m_gfxShape->m_numvertices,
|
||||
indices,
|
||||
meshData.m_gfxShape->m_numIndices, meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
|
||||
meshData.m_gfxShape->m_numIndices,color, meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
|
||||
|
||||
|
||||
m_internalData->m_renderObjects.push_back(ob);
|
||||
|
@ -687,7 +687,7 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC
|
||||
b3Assert(command);
|
||||
command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA;
|
||||
command->m_requestPixelDataArguments.m_startPixelIndex = 0;
|
||||
command->m_updateFlags = REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
|
||||
command->m_updateFlags = 0;//REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
|
@ -21,8 +21,8 @@ struct MyMotorInfo2
|
||||
int m_qIndex;
|
||||
};
|
||||
|
||||
int camVisualizerWidth = 1024/3;
|
||||
int camVisualizerHeight = 768/3;
|
||||
int camVisualizerWidth = 640;//1024/3;
|
||||
int camVisualizerHeight = 480;//768/3;
|
||||
|
||||
|
||||
#define MAX_NUM_MOTORS 128
|
||||
@ -614,18 +614,20 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
{
|
||||
for (int j=0;j<imageData.m_pixelHeight;j++)
|
||||
{
|
||||
int xIndex = int(float(i)*(float(camVisualizerWidth)/float(imageData.m_pixelWidth)));
|
||||
int yIndex = int(float(j)*(float(camVisualizerHeight)/float(imageData.m_pixelHeight)));
|
||||
int xIndex = int(float(i)*(float(camVisualizerWidth)/float(imageData.m_pixelWidth)));
|
||||
int yIndex = int(float(j)*(float(camVisualizerHeight)/float(imageData.m_pixelHeight)));
|
||||
btClamp(yIndex,0,imageData.m_pixelHeight);
|
||||
btClamp(xIndex,0,imageData.m_pixelWidth);
|
||||
int bytesPerPixel = 4;
|
||||
|
||||
int pixelIndex = (i+j*imageData.m_pixelWidth)*bytesPerPixel;
|
||||
m_canvas->setPixel(m_canvasIndex,xIndex,camVisualizerHeight-1-yIndex,
|
||||
|
||||
imageData.m_rgbColorData[pixelIndex],
|
||||
imageData.m_rgbColorData[pixelIndex+1],
|
||||
imageData.m_rgbColorData[pixelIndex+2],
|
||||
imageData.m_rgbColorData[pixelIndex+3]);
|
||||
255);
|
||||
// imageData.m_rgbColorData[pixelIndex+3]);
|
||||
}
|
||||
}
|
||||
m_canvas->refreshImageData(m_canvasIndex);
|
||||
|
@ -438,12 +438,18 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
|
||||
m_data->m_cachedCameraPixelsWidth = 0;
|
||||
m_data->m_cachedCameraPixelsHeight = 0;
|
||||
|
||||
|
||||
int numPixels = serverCmd.m_sendPixelDataArguments.m_imageWidth*serverCmd.m_sendPixelDataArguments.m_imageHeight;
|
||||
|
||||
m_data->m_cachedCameraPixelsRGBA.reserve(numPixels*numBytesPerPixel);
|
||||
m_data->m_cachedCameraDepthBuffer.resize(numTotalPixels);
|
||||
m_data->m_cachedCameraPixelsRGBA.resize(numTotalPixels*numBytesPerPixel);
|
||||
|
||||
|
||||
unsigned char* rgbaPixelsReceived =
|
||||
(unsigned char*)&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0];
|
||||
|
||||
printf("pixel = %d\n", rgbaPixelsReceived[0]);
|
||||
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*numBytesPerPixel;i++)
|
||||
{
|
||||
m_data->m_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel]
|
||||
|
@ -976,24 +976,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0);
|
||||
}
|
||||
//else
|
||||
else
|
||||
{
|
||||
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
||||
{
|
||||
printf("-------------------------------\nRendering\n");
|
||||
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
m_data->m_visualConverter.render(
|
||||
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
|
||||
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
||||
} else
|
||||
{
|
||||
m_data->m_visualConverter.render();
|
||||
}
|
||||
|
||||
}
|
||||
m_data->m_visualConverter.getWidthAndHeight(width,height);
|
||||
}
|
||||
|
||||
|
||||
@ -1015,7 +1000,24 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied);
|
||||
} else
|
||||
{
|
||||
|
||||
|
||||
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
|
||||
{
|
||||
printf("-------------------------------\nRendering\n");
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
m_data->m_visualConverter.render(
|
||||
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
|
||||
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
||||
} else
|
||||
{
|
||||
m_data->m_visualConverter.render();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied);
|
||||
}
|
||||
|
||||
//each pixel takes 4 RGBA values and 1 float = 8 bytes
|
||||
|
@ -437,9 +437,14 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const
|
||||
btTransform childTrans = vis.m_linkLocalFrame;
|
||||
btHashString matName(vis.m_materialName.c_str());
|
||||
UrdfMaterial *const * matPtr = model.m_materials[matName];
|
||||
|
||||
float rgbaColor[4] = {1,1,1,1};
|
||||
|
||||
if (matPtr)
|
||||
{
|
||||
UrdfMaterial *const mat = *matPtr;
|
||||
for (int i=0;i<4;i++)
|
||||
rgbaColor[i] = mat->m_rgbaColor[i];
|
||||
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
|
||||
//m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
}
|
||||
@ -458,7 +463,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const
|
||||
if (vertices.size() && indices.size())
|
||||
{
|
||||
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_swWidth,m_data->m_swHeight,m_data->m_rgbColorBuffer,m_data->m_depthBuffer);
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size());
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor);
|
||||
visuals->m_renderObjects.push_back(tinyObj);
|
||||
}
|
||||
}
|
||||
@ -579,6 +584,51 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height)
|
||||
{
|
||||
width = m_data->m_swWidth;
|
||||
height = m_data->m_swHeight;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
||||
{
|
||||
int w = m_data->m_rgbColorBuffer.get_width();
|
||||
int h = m_data->m_rgbColorBuffer.get_height();
|
||||
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
|
||||
if (widthPtr)
|
||||
*widthPtr = w;
|
||||
|
||||
if (heightPtr)
|
||||
*heightPtr = h;
|
||||
|
||||
int numTotalPixels = w*h;
|
||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||
int numBytesPerPixel = 4;//RGBA
|
||||
int numRequestedPixels = btMin(rgbaBufferSizeInPixels,numRemainingPixels);
|
||||
if (numRequestedPixels)
|
||||
{
|
||||
for (int i=0;i<numRequestedPixels;i++)
|
||||
{
|
||||
if (pixelsRGBA)
|
||||
{
|
||||
pixelsRGBA[i*numBytesPerPixel] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+0];
|
||||
pixelsRGBA[i*numBytesPerPixel+1] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+1];
|
||||
pixelsRGBA[i*numBytesPerPixel+2] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+2];
|
||||
pixelsRGBA[i*numBytesPerPixel+3] = 255;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = numRequestedPixels;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::resetAll()
|
||||
{
|
||||
//todo: free memory
|
||||
|
@ -23,6 +23,10 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
|
||||
void resetAll();
|
||||
|
||||
void getWidthAndHeight(int& width, int& height);
|
||||
|
||||
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
|
||||
void render();
|
||||
void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
|
@ -25,20 +25,21 @@ struct Shader : public IShader {
|
||||
Matrix& m_modelView1;
|
||||
Matrix& m_projectionMatrix;
|
||||
Vec3f m_localScaling;
|
||||
//Vec3f m_localNormal;
|
||||
Vec4f m_colorRGBA;
|
||||
|
||||
mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader
|
||||
mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS
|
||||
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
|
||||
//mat<3,3,float> ndc_tri; // triangle in normalized device coordinates
|
||||
|
||||
Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling)
|
||||
Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA)
|
||||
:m_model(model),
|
||||
m_light_dir_local(light_dir_local),
|
||||
m_modelView1(modelView),
|
||||
m_projectionMatrix(projectionMatrix),
|
||||
m_modelMat(modelMat),
|
||||
m_localScaling(localScaling)
|
||||
m_localScaling(localScaling),
|
||||
m_colorRGBA(colorRGBA)
|
||||
{
|
||||
m_invModelMat = m_modelMat.invert_transpose();
|
||||
}
|
||||
@ -75,6 +76,11 @@ struct Shader : public IShader {
|
||||
float diff = ambient+b3Min(b3Max(0.f, bn*m_light_dir_local),(1-ambient));
|
||||
//float diff = b3Max(0.f, n*m_light_dir_local);
|
||||
color = m_model->diffuse(uv)*diff;
|
||||
//colors are store in BGRA?
|
||||
color = TGAColor(color[0]*m_colorRGBA[2],
|
||||
color[1]*m_colorRGBA[1],
|
||||
color[2]*m_colorRGBA[0],
|
||||
color[3]*m_colorRGBA[3]);
|
||||
|
||||
return false;
|
||||
}
|
||||
@ -118,22 +124,24 @@ void TinyRenderObjectData::loadModel(const char* fileName)
|
||||
}
|
||||
|
||||
|
||||
void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices,
|
||||
void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices, const float rgbaColor[4],
|
||||
unsigned char* textureImage, int textureWidth, int textureHeight)
|
||||
{
|
||||
if (0==m_model)
|
||||
{
|
||||
m_model = new Model();
|
||||
m_model->setColorRGBA(rgbaColor);
|
||||
if (textureImage)
|
||||
{
|
||||
m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight);
|
||||
} else
|
||||
{
|
||||
char relativeFileName[1024];
|
||||
/*char relativeFileName[1024];
|
||||
if (b3ResourcePath::findResourcePath("floor_diffuse.tga", relativeFileName, 1024))
|
||||
{
|
||||
m_model->loadDiffuseTexture(relativeFileName);
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
for (int i=0;i<numVertices;i++)
|
||||
@ -254,7 +262,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
||||
{
|
||||
Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix;
|
||||
Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]);
|
||||
Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling);
|
||||
Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA());
|
||||
|
||||
printf("Render %d triangles.\n",model->nfaces());
|
||||
for (int i=0; i<model->nfaces(); i++)
|
||||
|
@ -35,7 +35,7 @@ struct TinyRenderObjectData
|
||||
|
||||
void loadModel(const char* fileName);
|
||||
void createCube(float HalfExtentsX,float HalfExtentsY,float HalfExtentsZ);
|
||||
void registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices,
|
||||
void registerMeshShape(const float* vertices, int numVertices,const int* indices, int numIndices, const float rgbaColor[4],
|
||||
unsigned char* textureImage=0, int textureWidth=0, int textureHeight=0);
|
||||
|
||||
void registerMesh2(btAlignedObjectArray<btVector3>& vertices, btAlignedObjectArray<btVector3>& normals,btAlignedObjectArray<int>& indices);
|
||||
|
@ -130,8 +130,12 @@ void Model::load_texture(std::string filename, const char *suffix, TGAImage &img
|
||||
}
|
||||
|
||||
TGAColor Model::diffuse(Vec2f uvf) {
|
||||
Vec2i uv(uvf[0]*diffusemap_.get_width(), uvf[1]*diffusemap_.get_height());
|
||||
return diffusemap_.get(uv[0], uv[1]);
|
||||
if (diffusemap_.get_width() && diffusemap_.get_height())
|
||||
{
|
||||
Vec2i uv(uvf[0]*diffusemap_.get_width(), uvf[1]*diffusemap_.get_height());
|
||||
return diffusemap_.get(uv[0], uv[1]);
|
||||
}
|
||||
return TGAColor(255,255,255,255);
|
||||
}
|
||||
|
||||
Vec3f Model::normal(Vec2f uvf) {
|
||||
|
@ -14,10 +14,22 @@ private:
|
||||
TGAImage diffusemap_;
|
||||
TGAImage normalmap_;
|
||||
TGAImage specularmap_;
|
||||
Vec4f m_colorRGBA;
|
||||
|
||||
void load_texture(std::string filename, const char *suffix, TGAImage &img);
|
||||
public:
|
||||
Model(const char *filename);
|
||||
Model();
|
||||
void setColorRGBA(const float rgba[4])
|
||||
{
|
||||
for (int i=0;i<4;i++)
|
||||
m_colorRGBA[i] = rgba[i];
|
||||
}
|
||||
|
||||
const Vec4f& getColorRGBA() const
|
||||
{
|
||||
return m_colorRGBA;
|
||||
}
|
||||
void loadDiffuseTexture(const char* relativeFileName);
|
||||
void setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight);
|
||||
void addVertex(float x,float y,float z, float normalX, float normalY, float normalZ, float u, float v);
|
||||
|
Loading…
Reference in New Issue
Block a user