initial hookup of TinyRenderer to shared memory interface
This commit is contained in:
@@ -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]);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user