add option to use hardware OpenGL renderer for synthetic camera
This commit is contained in:
@@ -46,7 +46,7 @@ struct GUIHelperInterface
|
||||
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0;
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)=0;
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)=0;
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) =0;
|
||||
|
||||
@@ -107,12 +107,8 @@ struct DummyGUIHelper : public GUIHelperInterface
|
||||
{
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int width, int height, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
@@ -77,7 +77,7 @@ struct CommonGraphicsApp
|
||||
virtual void dumpNextFrameToPng(const char* pngFilename){}
|
||||
virtual void dumpFramesToVideo(const char* mp4Filename){}
|
||||
|
||||
virtual void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes){};
|
||||
virtual void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes, float* depthBuffer, int depthBufferSizeInBytes){}
|
||||
|
||||
virtual void getBackgroundColor(float* red, float* green, float* blue) const
|
||||
{
|
||||
|
||||
@@ -970,14 +970,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
||||
s_instancingRenderer->updateCamera(dg.upAxis);
|
||||
}
|
||||
|
||||
if (renderGrid)
|
||||
{
|
||||
BT_PROFILE("Draw Grid");
|
||||
glPolygonOffset(3.0, 3);
|
||||
glEnable(GL_POLYGON_OFFSET_FILL);
|
||||
s_app->drawGrid(dg);
|
||||
|
||||
}
|
||||
|
||||
static int frameCount = 0;
|
||||
frameCount++;
|
||||
|
||||
@@ -1025,6 +1018,14 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
||||
}
|
||||
}
|
||||
|
||||
if (renderGrid)
|
||||
{
|
||||
BT_PROFILE("Draw Grid");
|
||||
glPolygonOffset(3.0, 3);
|
||||
glEnable(GL_POLYGON_OFFSET_FILL);
|
||||
s_app->drawGrid(dg);
|
||||
|
||||
}
|
||||
if (renderVisualGeometry && ((gDebugDrawFlags&btIDebugDraw::DBG_DrawWireframe)==0))
|
||||
{
|
||||
if (visualWireframe)
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include "CollisionShape2TriangleMesh.h"
|
||||
|
||||
|
||||
|
||||
#include "../OpenGLWindow/SimpleCamera.h"
|
||||
#include "../OpenGLWindow/GLInstanceGraphicsShape.h"
|
||||
//backwards compatibility
|
||||
#include "GL_ShapeDrawer.h"
|
||||
@@ -144,8 +144,8 @@ struct OpenGLGuiHelperInternalData
|
||||
class MyDebugDrawer* m_debugDraw;
|
||||
GL_ShapeDrawer* m_gl2ShapeDrawer;
|
||||
|
||||
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer;
|
||||
btAlignedObjectArray<float> m_depthBuffer;
|
||||
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer1;
|
||||
btAlignedObjectArray<float> m_depthBuffer1;
|
||||
};
|
||||
|
||||
|
||||
@@ -337,19 +337,15 @@ 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)
|
||||
void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
|
||||
{
|
||||
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();
|
||||
int sourceWidth = m_data->m_glApp->m_window->getWidth()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
int sourceHeight = m_data->m_glApp->m_window->getHeight()*m_data->m_glApp->m_window->getRetinaScale();
|
||||
|
||||
if (widthPtr)
|
||||
*widthPtr = w;
|
||||
if (heightPtr)
|
||||
*heightPtr = h;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
|
||||
int numTotalPixels = w*h;
|
||||
int numTotalPixels = destinationWidth*destinationHeight;
|
||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||
int numBytesPerPixel = 4;//RGBA
|
||||
int numRequestedPixels = btMin(rgbaBufferSizeInPixels,numRemainingPixels);
|
||||
@@ -357,22 +353,58 @@ void OpenGLGuiHelper::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBuf
|
||||
{
|
||||
if (startPixelIndex==0)
|
||||
{
|
||||
|
||||
//quick test: render the scene
|
||||
CommonCameraInterface* oldCam = getRenderInterface()->getActiveCamera();
|
||||
SimpleCamera tempCam;
|
||||
getRenderInterface()->setActiveCamera(&tempCam);
|
||||
getRenderInterface()->getActiveCamera()->setVRCamera(viewMatrix,projectionMatrix);
|
||||
getRenderInterface()->renderScene();
|
||||
//copy the image into our local cache
|
||||
m_data->m_rgbaPixelBuffer.resize(w*h*numBytesPerPixel);
|
||||
m_data->m_depthBuffer.resize(w*h);
|
||||
m_data->m_glApp->getScreenPixels(&(m_data->m_rgbaPixelBuffer[0]),m_data->m_rgbaPixelBuffer.size());
|
||||
}
|
||||
for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++)
|
||||
{
|
||||
if (pixelsRGBA)
|
||||
{
|
||||
pixelsRGBA[i] = m_data->m_rgbaPixelBuffer[i+startPixelIndex*numBytesPerPixel];
|
||||
getRenderInterface()->setActiveCamera(oldCam);
|
||||
|
||||
{
|
||||
btAlignedObjectArray<unsigned char> sourceRgbaPixelBuffer;
|
||||
btAlignedObjectArray<float> sourceDepthBuffer;
|
||||
//copy the image into our local cache
|
||||
sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel);
|
||||
sourceDepthBuffer.resize(sourceWidth*sourceHeight);
|
||||
m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size());
|
||||
|
||||
m_data->m_rgbaPixelBuffer1.resize(destinationWidth*destinationHeight*numBytesPerPixel);
|
||||
m_data->m_depthBuffer1.resize(destinationWidth*destinationHeight);
|
||||
//rescale and flip
|
||||
|
||||
for (int i=0;i<destinationWidth;i++)
|
||||
{
|
||||
for (int j=0;j<destinationHeight;j++)
|
||||
{
|
||||
int xIndex = int(float(i)*(float(sourceWidth)/float(destinationWidth)));
|
||||
int yIndex = int(float(destinationHeight-1-j)*(float(sourceHeight)/float(destinationHeight)));
|
||||
btClamp(xIndex,0,sourceWidth);
|
||||
btClamp(yIndex,0,sourceHeight);
|
||||
int bytesPerPixel = 4; //RGBA
|
||||
|
||||
int sourcePixelIndex = (xIndex+yIndex*sourceWidth)*bytesPerPixel;
|
||||
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0];
|
||||
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1];
|
||||
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2];
|
||||
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
if (pixelsRGBA)
|
||||
{
|
||||
for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++)
|
||||
{
|
||||
pixelsRGBA[i] = m_data->m_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel];
|
||||
}
|
||||
}
|
||||
if (depthBuffer)
|
||||
{
|
||||
for (int i=0;i<numRequestedPixels;i++)
|
||||
{
|
||||
depthBuffer[i] = m_data->m_depthBuffer1[i];
|
||||
}
|
||||
}
|
||||
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = numRequestedPixels;
|
||||
|
||||
|
||||
@@ -44,7 +44,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied);
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied);
|
||||
|
||||
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld) ;
|
||||
|
||||
|
||||
@@ -200,7 +200,7 @@ void ImportUrdfSetup::initPhysics()
|
||||
|
||||
|
||||
btVector3 gravity(0,0,0);
|
||||
//gravity[upAxis]=-9.8;
|
||||
gravity[upAxis]=-9.8;
|
||||
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
@@ -342,7 +342,7 @@ void ImportUrdfSetup::initPhysics()
|
||||
|
||||
|
||||
|
||||
bool createGround=false;
|
||||
bool createGround=true;
|
||||
if (createGround)
|
||||
{
|
||||
btVector3 groundHalfExtents(20,20,20);
|
||||
|
||||
@@ -146,8 +146,9 @@ struct InternalTextureHandle
|
||||
struct InternalDataRenderer : public GLInstanceRendererInternalData
|
||||
{
|
||||
|
||||
SimpleCamera m_defaultCamera;
|
||||
|
||||
SimpleCamera m_defaultCamera1;
|
||||
CommonCameraInterface* m_activeCamera;
|
||||
|
||||
GLfloat m_projectionMatrix[16];
|
||||
GLfloat m_viewMatrix[16];
|
||||
|
||||
@@ -164,7 +165,8 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
|
||||
InternalDataRenderer() :
|
||||
m_shadowMap(0),
|
||||
m_shadowTexture(0),
|
||||
m_renderFrameBuffer(0)
|
||||
m_renderFrameBuffer(0),
|
||||
m_activeCamera(&m_defaultCamera1)
|
||||
{
|
||||
//clear to zero to make it obvious if the matrix is used uninitialized
|
||||
for (int i=0;i<16;i++)
|
||||
@@ -919,18 +921,18 @@ void GLInstancingRenderer::resize(int width, int height)
|
||||
|
||||
const CommonCameraInterface* GLInstancingRenderer::getActiveCamera() const
|
||||
{
|
||||
return &m_data->m_defaultCamera;
|
||||
return m_data->m_activeCamera;
|
||||
}
|
||||
|
||||
CommonCameraInterface* GLInstancingRenderer::getActiveCamera()
|
||||
{
|
||||
return &m_data->m_defaultCamera;
|
||||
return m_data->m_activeCamera;
|
||||
}
|
||||
|
||||
|
||||
void GLInstancingRenderer::setActiveCamera(CommonCameraInterface* cam)
|
||||
{
|
||||
b3Assert(0);//not supported yet
|
||||
m_data->m_activeCamera = cam;
|
||||
}
|
||||
|
||||
|
||||
@@ -951,14 +953,10 @@ void GLInstancingRenderer::updateCamera(int upAxis)
|
||||
b3Assert(0);
|
||||
};
|
||||
|
||||
m_data->m_defaultCamera.setCameraUpAxis(upAxis);
|
||||
m_data->m_defaultCamera.setAspectRatio((float)m_screenWidth/(float)m_screenHeight);
|
||||
m_data->m_defaultCamera.update();
|
||||
m_data->m_activeCamera->setCameraUpAxis(upAxis);
|
||||
m_data->m_activeCamera->setAspectRatio((float)m_screenWidth/(float)m_screenHeight);
|
||||
m_data->m_defaultCamera1.update();
|
||||
|
||||
m_data->m_defaultCamera.getCameraProjectionMatrix(m_data->m_projectionMatrix);
|
||||
m_data->m_defaultCamera.getCameraViewMatrix(m_data->m_viewMatrix);
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -1489,7 +1487,7 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
|
||||
float depthViewMatrix[4][4];
|
||||
b3Vector3 center = b3MakeVector3(0,0,0);
|
||||
float upf[3];
|
||||
m_data->m_defaultCamera.getCameraUpVector(upf);
|
||||
m_data->m_activeCamera->getCameraUpVector(upf);
|
||||
b3Vector3 up = b3MakeVector3(upf[0],upf[1],upf[2]);
|
||||
b3CreateLookAt(gLightPos,center,up,&depthViewMatrix[0][0]);
|
||||
//b3CreateLookAt(lightPos,m_data->m_cameraTargetPosition,b3Vector3(0,1,0),(float*)depthModelViewMatrix2);
|
||||
@@ -1526,6 +1524,9 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
|
||||
{
|
||||
B3_PROFILE("updateCamera");
|
||||
// updateCamera();
|
||||
m_data->m_activeCamera->getCameraProjectionMatrix(m_data->m_projectionMatrix);
|
||||
m_data->m_activeCamera->getCameraViewMatrix(m_data->m_viewMatrix);
|
||||
|
||||
}
|
||||
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
@@ -657,7 +657,7 @@ SimpleOpenGL3App::~SimpleOpenGL3App()
|
||||
delete m_data ;
|
||||
}
|
||||
|
||||
void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes)
|
||||
void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes, float* depthBuffer, int depthBufferSizeInBytes)
|
||||
{
|
||||
|
||||
int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth();
|
||||
@@ -668,6 +668,12 @@ void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSize
|
||||
int glstat = glGetError();
|
||||
b3Assert(glstat==GL_NO_ERROR);
|
||||
}
|
||||
if ((width*height*sizeof(float)) == depthBufferSizeInBytes)
|
||||
{
|
||||
glReadPixels(0,0,width, height, GL_DEPTH_COMPONENT, GL_FLOAT, depthBuffer);
|
||||
int glstat = glGetError();
|
||||
b3Assert(glstat==GL_NO_ERROR);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
|
||||
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4]);
|
||||
void dumpNextFrameToPng(const char* pngFilename);
|
||||
void dumpFramesToVideo(const char* mp4Filename);
|
||||
void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes);
|
||||
void getScreenPixels(unsigned char* rgbaBuffer, int bufferSizeInBytes, float* depthBuffer, int depthBufferSizeInBytes);
|
||||
|
||||
void drawGrid(DrawGridData data=DrawGridData());
|
||||
virtual void setUpAxis(int axis);
|
||||
|
||||
@@ -345,12 +345,8 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
@@ -792,6 +792,14 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||
b3Assert(renderer>(1<<15));
|
||||
command->m_updateFlags |= renderer;
|
||||
}
|
||||
|
||||
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
|
||||
{
|
||||
|
||||
@@ -73,6 +73,7 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command,
|
||||
void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]);
|
||||
void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal);
|
||||
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
|
||||
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
|
||||
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
||||
|
||||
|
||||
|
||||
@@ -170,8 +170,9 @@ protected:
|
||||
// b3Printf("# motors = %d, cmd[%d] qIndex = %d, uIndex = %d, targetPos = %f", m_numMotors, serial, qIndex,uIndex,targetPos);
|
||||
|
||||
b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos);
|
||||
b3JointControlSetKp(commandHandle, qIndex, 0.1);
|
||||
b3JointControlSetKd(commandHandle, uIndex, 0);
|
||||
b3JointControlSetDesiredVelocity(commandHandle,uIndex,0);
|
||||
b3JointControlSetKp(commandHandle, qIndex, 0.01);
|
||||
b3JointControlSetKd(commandHandle, uIndex, 0.1);
|
||||
|
||||
b3JointControlSetMaximumForce(commandHandle,uIndex,1000);
|
||||
}
|
||||
@@ -236,7 +237,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf");
|
||||
//setting the initial position, orientation and other arguments are optional
|
||||
double startPosX = 0;
|
||||
static double startPosY = 0;
|
||||
static double startPosY = 1;
|
||||
double startPosZ = 0;
|
||||
b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX,startPosY,startPosZ);
|
||||
startPosY += 2.f;
|
||||
@@ -256,11 +257,13 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
///request an image from a simulated camera, using a software renderer.
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
|
||||
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
|
||||
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
@@ -483,9 +486,9 @@ void PhysicsClientExample::createButtons()
|
||||
}
|
||||
createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
|
||||
createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
|
||||
createButton("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
|
||||
createButton("Create Cylinder Body",CMD_CREATE_RIGID_BODY,isTrigger);
|
||||
createButton("Reset Simulation",CMD_RESET_SIMULATION,isTrigger);
|
||||
createButton("Initialize Pose",CMD_INIT_POSE, isTrigger);
|
||||
createButton("Initialize Pose",CMD_INIT_POSE, isTrigger);
|
||||
createButton("Set gravity", CMD_SEND_PHYSICS_SIMULATION_PARAMETERS, isTrigger);
|
||||
|
||||
if (m_bodyUniqueIds.size())
|
||||
@@ -681,7 +684,6 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
|
||||
int pixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel;
|
||||
m_canvas->setPixel(m_canvasIndex,i,j,
|
||||
|
||||
imageData.m_rgbColorData[pixelIndex],
|
||||
imageData.m_rgbColorData[pixelIndex+1],
|
||||
imageData.m_rgbColorData[pixelIndex+2],
|
||||
|
||||
@@ -1123,23 +1123,24 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
|
||||
int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex;
|
||||
int width, height;
|
||||
int width = clientCmd.m_requestPixelDataArguments.m_pixelWidth;
|
||||
int height = clientCmd.m_requestPixelDataArguments.m_pixelHeight;
|
||||
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)
|
||||
if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0);
|
||||
//m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,clientCmd.m_requestPixelDataArguments.m_projectionMatrix,0,0,0,0,0,width,height,0);
|
||||
}
|
||||
else
|
||||
{
|
||||
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);
|
||||
}
|
||||
m_data->m_visualConverter.getWidthAndHeight(width,height);
|
||||
}
|
||||
|
||||
@@ -1157,9 +1158,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4);
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0)
|
||||
if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
|
||||
{
|
||||
m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied);
|
||||
m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,clientCmd.m_requestPixelDataArguments.m_projectionMatrix,pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,width,height,&numPixelsCopied);
|
||||
} else
|
||||
{
|
||||
|
||||
|
||||
@@ -346,12 +346,8 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int width, int height, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
@@ -138,8 +138,8 @@ struct RequestPixelDataArgs
|
||||
enum EnumRequestPixelDataUpdateFlags
|
||||
{
|
||||
REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1,
|
||||
REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL=2,
|
||||
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4,
|
||||
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -151,4 +151,12 @@ enum EnumExternalForceFlags
|
||||
EF_WORLD_FRAME=2,
|
||||
};
|
||||
|
||||
///flags to pick the renderer for synthetic camera
|
||||
enum EnumRenderer
|
||||
{
|
||||
ER_TINY_RENDERER=(1<<16),
|
||||
ER_BULLET_HARDWARE_OPENGL=(1<<17),
|
||||
//ER_FIRE_RAYS=(1<<18),
|
||||
};
|
||||
|
||||
#endif//SHARED_MEMORY_PUBLIC_H
|
||||
|
||||
@@ -348,12 +348,8 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
|
||||
|
||||
}
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
|
||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int width, int height, int* numPixelsCopied)
|
||||
{
|
||||
if (width)
|
||||
*width = 0;
|
||||
if (height)
|
||||
*height = 0;
|
||||
if (numPixelsCopied)
|
||||
*numPixelsCopied = 0;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user