implement pybullet.getDebugVisualizerCamera, width, height, providing viewmatrix, projection matrix

This commit is contained in:
Erwin Coumans
2017-04-10 11:03:41 -07:00
parent 82b6bc8770
commit bdf366b045
16 changed files with 284 additions and 9 deletions

View File

@@ -2843,6 +2843,33 @@ void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle comman
}
}
b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_REQUEST_OPENGL_VISUALIZER_CAMERA;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, b3OpenGLVisualizerCameraInfo* camera)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
//b3Assert(status);
if (status && status->m_type == CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED)
{
*camera = status->m_visualizerCameraResultArgs;
return 1;
}
return 0;
}
void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds)
{
PhysicsClient* cl = (PhysicsClient*)physClient;

View File

@@ -104,6 +104,9 @@ b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandl
void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled);
void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]);
b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient);
int b3GetStatusOpenGLVisualizerCamera(b3SharedMemoryStatusHandle statusHandle, struct b3OpenGLVisualizerCameraInfo* camera);
/// Add/remove user-specific debug lines and debug text messages
b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime);

View File

@@ -990,6 +990,16 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
b3Warning("State Logging failed");
break;
}
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED:
{
b3Warning("Request visualizer camera failed");
break;
}
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED:
{
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);
btAssert(0);

View File

@@ -834,6 +834,16 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
break;
}
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED:
{
break;
}
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED:
{
b3Warning("requestOpenGLVisualizeCamera failed");
break;
}
case CMD_REMOVE_USER_CONSTRAINT_FAILED:
{
b3Warning("removeConstraint failed");

View File

@@ -4186,6 +4186,24 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA:
{
BT_PROFILE("CMD_REQUEST_OPENGL_VISUALIZER_CAMERA");
SharedMemoryStatus& serverCmd = serverStatusOut;
bool result = this->m_data->m_guiHelper->getCameraInfo(
&serverCmd.m_visualizerCameraResultArgs.m_width,
&serverCmd.m_visualizerCameraResultArgs.m_height,
serverCmd.m_visualizerCameraResultArgs.m_viewMatrix,
serverCmd.m_visualizerCameraResultArgs.m_projectionMatrix,
serverCmd.m_visualizerCameraResultArgs.m_camUp,
serverCmd.m_visualizerCameraResultArgs.m_camForward,
serverCmd.m_visualizerCameraResultArgs.m_horizontal,
serverCmd.m_visualizerCameraResultArgs.m_vertical);
serverCmd.m_type = result ? CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED: CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED;
hasStatus = true;
break;
}
case CMD_CONFIGURE_OPENGL_VISUALIZER:
{
BT_PROFILE("CMD_CONFIGURE_OPENGL_VISUALIZER");

View File

@@ -808,6 +808,12 @@ public:
m_childGuiHelper->resetCamera(camDist,pitch,yaw,camPosX,camPosY,camPosZ);
}
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const
{
return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert);
}
float m_viewMatrix[16];
float m_projectionMatrix[16];
unsigned char* m_pixelsRGBA;

View File

@@ -790,7 +790,7 @@ struct SharedMemoryStatus
struct SendKeyboardEvents m_sendKeyboardEvents;
struct SendRaycastHits m_raycastHits;
struct StateLoggingResultArgs m_stateLoggingResultArgs;
struct b3OpenGLVisualizerCameraInfo m_visualizerCameraResultArgs;
};
};

View File

@@ -54,6 +54,7 @@ enum EnumSharedMemoryClientCommand
CMD_STATE_LOGGING,
CMD_CONFIGURE_OPENGL_VISUALIZER,
CMD_REQUEST_KEYBOARD_EVENTS_DATA,
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -133,6 +134,8 @@ enum EnumSharedMemoryServerStatus
CMD_STATE_LOGGING_FAILED,
CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED,
CMD_REQUEST_KEYBOARD_EVENTS_DATA_FAILED,
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED,
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -248,6 +251,19 @@ struct b3CameraImageData
const int* m_segmentationMaskValues;//m_pixelWidth*m_pixelHeight ints
};
struct b3OpenGLVisualizerCameraInfo
{
int m_width;
int m_height;
float m_viewMatrix[16];
float m_projectionMatrix[16];
float m_camUp[3];
float m_camForward[3];
float m_horizontal[3];
float m_vertical[3];
};
enum b3VREventType
{