diff options
author | Erwin Coumans <erwincoumans@google.com> | 2017-02-21 17:36:54 -0800 |
---|---|---|
committer | Erwin Coumans <erwincoumans@google.com> | 2017-02-21 17:36:54 -0800 |
commit | 37890e5a4dc597c15ad2769d9e3dfb0e8a26ec2f (patch) | |
tree | 6dab7b2e807a8f8806532fb87bce939db19e0085 /examples | |
parent | 5c74b0a1997bcfc1209275ad50ebee66e43d8fb4 (diff) | |
download | bullet3-37890e5a4dc597c15ad2769d9e3dfb0e8a26ec2f.tar.gz |
allow to enable/disable GUI, shadows, wireframe of OpenGL Visualizer from API
(pybullet.configureDebugVisualizer)
Diffstat (limited to 'examples')
-rw-r--r-- | examples/CommonInterfaces/CommonGUIHelperInterface.h | 2 | ||||
-rw-r--r-- | examples/ExampleBrowser/OpenGLExampleBrowser.cpp | 4 | ||||
-rw-r--r-- | examples/ExampleBrowser/OpenGLGuiHelper.cpp | 24 | ||||
-rw-r--r-- | examples/ExampleBrowser/OpenGLGuiHelper.h | 2 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsClientC_API.cpp | 47 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsClientC_API.h | 6 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsClientTCP.cpp | 1 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 26 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsServerExample.cpp | 7 | ||||
-rw-r--r-- | examples/SharedMemory/SharedMemoryCommands.h | 18 | ||||
-rw-r--r-- | examples/SharedMemory/SharedMemoryPublic.h | 8 | ||||
-rw-r--r-- | examples/pybullet/pybullet.c | 41 |
12 files changed, 181 insertions, 5 deletions
diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 5ecd98273..73feb3198 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -46,6 +46,8 @@ struct GUIHelperInterface virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0; + virtual void setVisualizerFlag(int flag, int enable){}; + virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 9ffce6c96..74aaca1b4 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -125,10 +125,10 @@ bool sUseOpenGL2 = false; extern bool useShadowMap; #endif -static bool visualWireframe=false; +bool visualWireframe=false; static bool renderVisualGeometry=true; static bool renderGrid = true; -static bool renderGui = true; +bool renderGui = true; static bool enable_experimental_opencl = false; int gDebugDrawFlags = 0; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 87bff6e59..32a91d581 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -374,6 +374,30 @@ void OpenGLGuiHelper::setUpAxis(int axis) } +extern bool useShadowMap; +extern bool visualWireframe; +extern bool renderGui; +#include "../SharedMemory/SharedMemoryPublic.h" + +void OpenGLGuiHelper::setVisualizerFlag(int flag, int enable) +{ + //temporary direct access + if (flag == COV_ENABLE_SHADOWS) + { + useShadowMap = enable; + } + if (flag == COV_ENABLE_GUI) + { + renderGui = enable; + } + + if (flag == COV_ENABLE_WIREFRAME) + { + visualWireframe = enable; + } +} + + void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ) { if (getRenderInterface() && getRenderInterface()->getActiveCamera()) diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 642b9dea1..f2008ab5e 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -42,6 +42,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual void setUpAxis(int axis); + void setVisualizerFlag(int flag, int enable); + virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ); virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index b116999d6..b89d618f5 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -2551,3 +2551,50 @@ int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid return 0; } + +///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc) +b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + command->m_type = CMD_CONFIGURE_OPENGL_VISUALIZER; + command->m_updateFlags = 0; + + return (b3SharedMemoryCommandHandle)command; +} + +void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER); + if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER) + { + command->m_updateFlags |= COV_SET_FLAGS; + command->m_configureOpenGLVisualizerArguments.m_setFlag = flag; + command->m_configureOpenGLVisualizerArguments.m_setEnabled = enabled; + } +} + +void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER); + + if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER) + { + command->m_updateFlags |= COV_SET_CAMERA_VIEW_MATRIX; + command->m_configureOpenGLVisualizerArguments.m_cameraDistance = cameraDistance; + command->m_configureOpenGLVisualizerArguments.m_cameraPitch = cameraPitch; + command->m_configureOpenGLVisualizerArguments.m_cameraYaw = cameraYaw; + command->m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0] = cameraTargetPosition[0]; + command->m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1] = cameraTargetPosition[1]; + command->m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2] = cameraTargetPosition[2]; + } +} + diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b22b9635c..61638bb7f 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -98,7 +98,13 @@ b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle ///Get the pointers to the physics debug line information, after b3InitRequestDebugLinesCommand returns ///status CMD_DEBUG_LINES_COMPLETED void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines); + +///configure the 3D OpenGL debug visualizer (enable/disable GUI widgets, shadows, position camera etc) +b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient); +void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled); +void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]); + /// 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); b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime); diff --git a/examples/SharedMemory/PhysicsClientTCP.cpp b/examples/SharedMemory/PhysicsClientTCP.cpp index 443fc3bef..9ad9fdab9 100644 --- a/examples/SharedMemory/PhysicsClientTCP.cpp +++ b/examples/SharedMemory/PhysicsClientTCP.cpp @@ -175,7 +175,6 @@ bool TcpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryComma sz = sizeof(SharedMemoryCommand); data = (unsigned char*)&clientCmd; } - int res; m_data->m_tcpSocket.Send((const uint8 *)data,sz); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 0f7139257..3a6341e36 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -507,7 +507,7 @@ struct MinitaurStateLogger : public InternalStateLogger if (m_logFileHandle) { - btVector3 pos = m_minitaurMultiBody->getBasePos(); + //btVector3 pos = m_minitaurMultiBody->getBasePos(); MinitaurLogRecord logData; //'t', 'r', 'p', 'y', 'q0', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7', 'u0', 'u1', 'u2', 'u3', 'u4', 'u5', 'u6', 'u7', 'xd', 'mo' @@ -3385,6 +3385,30 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm hasStatus = true; break; } + + case CMD_CONFIGURE_OPENGL_VISUALIZER: + { + SharedMemoryStatus& serverCmd = serverStatusOut; + serverCmd.m_type =CMD_CLIENT_COMMAND_COMPLETED; + + hasStatus = true; + if (clientCmd.m_updateFlags&COV_SET_FLAGS) + { + m_data->m_guiHelper->setVisualizerFlag(clientCmd.m_configureOpenGLVisualizerArguments.m_setFlag, + clientCmd.m_configureOpenGLVisualizerArguments.m_setEnabled); + } + if (clientCmd.m_updateFlags&COV_SET_CAMERA_VIEW_MATRIX) + { + m_data->m_guiHelper->resetCamera( clientCmd.m_configureOpenGLVisualizerArguments.m_cameraDistance, + clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch, + clientCmd.m_configureOpenGLVisualizerArguments.m_cameraYaw, + clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0], + clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1], + clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]); + } + break; + } + case CMD_REQUEST_CONTACT_POINT_INFORMATION: { SharedMemoryStatus& serverCmd =serverStatusOut; diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 520a6d904..cb05ce921 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -504,6 +504,13 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface public: + + void setVisualizerFlag(int flag, int enable) + { + m_childGuiHelper->setVisualizerFlag(flag,enable); + } + + GUIHelperInterface* m_childGuiHelper; int m_uidGenerator; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 5bc2a508d..52a2ea53d 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -643,6 +643,23 @@ struct StateLoggingResultArgs int m_loggingUniqueId; }; +enum InternalOpenGLVisualizerUpdateFlags +{ + COV_SET_CAMERA_VIEW_MATRIX=1, + COV_SET_FLAGS=2, +}; + +struct ConfigureOpenGLVisualizerRequest +{ + double m_cameraDistance; + double m_cameraPitch; + double m_cameraYaw; + double m_cameraTargetPosition[3]; + + int m_setFlag; + int m_setEnabled; +}; + struct SharedMemoryCommand { int m_type; @@ -685,6 +702,7 @@ struct SharedMemoryCommand struct LoadBunnyArgs m_loadBunnyArguments; struct VRCameraState m_vrCameraStateArguments; struct StateLoggingRequest m_stateLoggingArguments; + struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 526a4ec4d..7fa209856 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -49,6 +49,7 @@ enum EnumSharedMemoryClientCommand CMD_SET_VR_CAMERA_STATE, CMD_SYNC_BODY_INFO, CMD_STATE_LOGGING, + CMD_CONFIGURE_OPENGL_VISUALIZER, //don't go beyond this command! CMD_MAX_CLIENT_COMMANDS, @@ -126,6 +127,7 @@ enum EnumSharedMemoryServerStatus CMD_STATE_LOGGING_COMPLETED, CMD_STATE_LOGGING_START_COMPLETED, CMD_STATE_LOGGING_FAILED, + //don't go beyond 'CMD_MAX_SERVER_COMMANDS! CMD_MAX_SERVER_COMMANDS }; @@ -398,4 +400,10 @@ enum EnumRenderer //ER_FIRE_RAYS=(1<<18), }; +enum EnumConfigureOpenGLVisualizer +{ + COV_ENABLE_GUI=1, + COV_ENABLE_SHADOWS, + COV_ENABLE_WIREFRAME, +}; #endif//SHARED_MEMORY_PUBLIC_H diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 179f052a0..00ddec83f 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2619,7 +2619,6 @@ static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyObject *keywds) { - b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int statusType; @@ -2958,6 +2957,36 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject * } +static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* args, PyObject *keywds) +{ + int flag=1; + int enable = -1; + + int physicsClientId = 0; + b3PhysicsClientHandle sm=0; + static char *kwlist[] = { "flag", "enable", "physicsClientId", NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iii", kwlist, + &flag, &enable, &physicsClientId)) + return NULL; + + sm = getPhysicsClient(physicsClientId); + if (sm == 0) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm); + b3ConfigureOpenGLVisualizerSetVisualizationFlags(commandHandle, flag, enable); + b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + } + Py_INCREF(Py_None); + return Py_None; +} + + static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, PyObject *keywds) { @@ -5051,6 +5080,10 @@ static PyMethodDef SpamMethods[] = { "If you ommit the color, the custom color will be removed." }, + { "configureDebugVisualizer", (PyCFunction)pybullet_configureDebugVisualizer, METH_VARARGS | METH_KEYWORDS, + "For the 3D OpenGL Visualizer, enable/disable GUI, shadows. Set the camera parameters." + }, + {"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS| METH_KEYWORDS, "Return the visual shape information for one object." }, @@ -5188,6 +5221,12 @@ initpybullet(void) PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT); PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS); + PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); + PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); + PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); + + + SpamError = PyErr_NewException("pybullet.error", NULL, NULL); Py_INCREF(SpamError); PyModule_AddObject(m, "error", SpamError); |