allow to enable/disable GUI, shadows, wireframe of OpenGL Visualizer from API
(pybullet.configureDebugVisualizer)
This commit is contained in:
@@ -2,7 +2,7 @@
|
||||
rm CMakeCache.txt
|
||||
mkdir build_cmake
|
||||
cd build_cmake
|
||||
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=OFF -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release ..
|
||||
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=OFF -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release -G Xcode ..
|
||||
make -j12
|
||||
cd examples
|
||||
cd pybullet
|
||||
|
||||
@@ -3,5 +3,5 @@ cd build3
|
||||
./premake4_linux64 gmake
|
||||
./premake4_osx gmake
|
||||
cd gmake
|
||||
make -j12
|
||||
make -j12 --double --enable_pybullet
|
||||
../../bin/App_BulletExampleBrowser_gmake_x64_release
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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())
|
||||
|
||||
@@ -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],
|
||||
|
||||
@@ -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];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
};
|
||||
};
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user