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

@@ -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);