fix issues related to camera width/height
add width,height as arguments to pybullet.renderImage(x,y,[viewMat4x4],[projMat4x4])
This commit is contained in:
@@ -735,6 +735,16 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa
|
||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES;
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height )
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||
command->m_requestPixelDataArguments.m_pixelWidth = width;
|
||||
command->m_requestPixelDataArguments.m_pixelHeight = height;
|
||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT;
|
||||
}
|
||||
|
||||
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
||||
@@ -68,6 +68,7 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
|
||||
///request an image from a simulated camera, using a software renderer.
|
||||
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
|
||||
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
|
||||
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
|
||||
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
||||
|
||||
|
||||
|
||||
@@ -21,8 +21,8 @@ struct MyMotorInfo2
|
||||
int m_qIndex;
|
||||
};
|
||||
|
||||
int camVisualizerWidth = 640;//1024/3;
|
||||
int camVisualizerHeight = 480;//768/3;
|
||||
int camVisualizerWidth = 320;//1024/3;
|
||||
int camVisualizerHeight = 240;//768/3;
|
||||
|
||||
|
||||
#define MAX_NUM_MOTORS 128
|
||||
@@ -77,10 +77,10 @@ protected:
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 5;
|
||||
float dist = 1.1;
|
||||
float pitch = 50;
|
||||
float yaw = 35;
|
||||
float targetPos[3]={0,0,0};//-3,2.8,-2.5};
|
||||
float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
|
||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
|
||||
}
|
||||
@@ -248,7 +248,8 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
case CMD_CREATE_BOX_COLLISION_SHAPE:
|
||||
@@ -619,18 +620,18 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
b3GetCameraImageData(m_physicsClientHandle,&imageData);
|
||||
if (m_canvas && m_canvasIndex >=0)
|
||||
{
|
||||
for (int i=0;i<imageData.m_pixelWidth;i++)
|
||||
for (int i=0;i<camVisualizerWidth;i++)
|
||||
{
|
||||
for (int j=0;j<imageData.m_pixelHeight;j++)
|
||||
for (int j=0;j<camVisualizerHeight;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(imageData.m_pixelWidth)/float(camVisualizerWidth)));
|
||||
int yIndex = int(float(j)*(float(imageData.m_pixelHeight)/float(camVisualizerHeight)));
|
||||
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,
|
||||
int pixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel;
|
||||
m_canvas->setPixel(m_canvasIndex,i,camVisualizerHeight-1-j,
|
||||
|
||||
imageData.m_rgbColorData[pixelIndex],
|
||||
imageData.m_rgbColorData[pixelIndex+1],
|
||||
|
||||
@@ -450,6 +450,13 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
(unsigned char*)&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0];
|
||||
// printf("pixel = %d\n", rgbaPixelsReceived[0]);
|
||||
|
||||
float* depthBuffer = (float*)&(m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*4]);
|
||||
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied;i++)
|
||||
{
|
||||
m_data->m_cachedCameraDepthBuffer[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex] = depthBuffer[i];
|
||||
}
|
||||
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*numBytesPerPixel;i++)
|
||||
{
|
||||
m_data->m_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel]
|
||||
|
||||
@@ -210,8 +210,15 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
|
||||
|
||||
unsigned char* rgbaPixelsReceived =
|
||||
(unsigned char*)&m_data->m_bulletStreamDataServerToClient[0];
|
||||
printf("pixel = %d\n", rgbaPixelsReceived[0]);
|
||||
|
||||
float* depthBuffer = (float*)&(m_data->m_bulletStreamDataServerToClient[serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*4]);
|
||||
|
||||
// printf("pixel = %d\n", rgbaPixelsReceived[0]);
|
||||
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied;i++)
|
||||
{
|
||||
m_data->m_cachedCameraDepthBuffer[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex] = depthBuffer[i];
|
||||
}
|
||||
for (int i=0;i<serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*numBytesPerPixel;i++)
|
||||
{
|
||||
m_data->m_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel]
|
||||
@@ -227,6 +234,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand)
|
||||
command.m_requestPixelDataArguments.m_startPixelIndex =
|
||||
serverCmd.m_sendPixelDataArguments.m_startingPixelIndex +
|
||||
serverCmd.m_sendPixelDataArguments.m_numPixelsCopied;
|
||||
|
||||
} else
|
||||
{
|
||||
m_data->m_cachedCameraPixelsWidth = serverCmd.m_sendPixelDataArguments.m_imageWidth;
|
||||
|
||||
@@ -972,6 +972,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
int width, height;
|
||||
int numPixelsCopied = 0;
|
||||
|
||||
if (
|
||||
(clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) &&
|
||||
(clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0)
|
||||
{
|
||||
m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
|
||||
clientCmd.m_requestPixelDataArguments.m_pixelHeight);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0)
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0);
|
||||
@@ -1005,6 +1013,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
// printf("-------------------------------\nRendering\n");
|
||||
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
m_data->m_visualConverter.render(
|
||||
|
||||
@@ -129,12 +129,16 @@ struct RequestPixelDataArgs
|
||||
float m_viewMatrix[16];
|
||||
float m_projectionMatrix[16];
|
||||
int m_startPixelIndex;
|
||||
int m_pixelWidth;
|
||||
int m_pixelHeight;
|
||||
};
|
||||
|
||||
enum EnumRequestPixelDataUpdateFlags
|
||||
{
|
||||
REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1,
|
||||
REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL=2,
|
||||
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4,
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -462,7 +462,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);
|
||||
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer);
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor);
|
||||
visuals->m_renderObjects.push_back(tinyObj);
|
||||
}
|
||||
@@ -576,7 +576,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
|
||||
renderObj->m_lightDirWorld = lightDirWorld;
|
||||
}
|
||||
}
|
||||
TinyRenderer::renderObject(*renderObj);
|
||||
TinyRenderer::renderObject(*renderObj,m_data->m_swWidth,m_data->m_swHeight);
|
||||
}
|
||||
}
|
||||
//printf("write tga \n");
|
||||
@@ -590,6 +590,17 @@ void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height
|
||||
height = m_data->m_swHeight;
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
|
||||
{
|
||||
m_data->m_swWidth = width;
|
||||
m_data->m_swHeight = height;
|
||||
|
||||
m_data->m_depthBuffer.resize(m_data->m_swWidth*m_data->m_swHeight);
|
||||
m_data->m_rgbColorBuffer = TGAImage(width, height, TGAImage::RGB);
|
||||
|
||||
}
|
||||
|
||||
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();
|
||||
@@ -612,6 +623,10 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
|
||||
{
|
||||
for (int i=0;i<numRequestedPixels;i++)
|
||||
{
|
||||
if (depthBuffer)
|
||||
{
|
||||
depthBuffer[i] = m_data->m_depthBuffer[i+startPixelIndex];
|
||||
}
|
||||
if (pixelsRGBA)
|
||||
{
|
||||
pixelsRGBA[i*numBytesPerPixel] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+0];
|
||||
|
||||
@@ -24,6 +24,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
void resetAll();
|
||||
|
||||
void getWidthAndHeight(int& width, int& height);
|
||||
void setWidthAndHeight(int width, int height);
|
||||
|
||||
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user