add option to use hardware OpenGL renderer for synthetic camera
This commit is contained in:
@@ -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
|
||||
|
||||
Reference in New Issue
Block a user