implement pybullet.getDebugVisualizerCamera, width, height, providing viewmatrix, projection matrix
This commit is contained in:
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user