Allow to configure Y=up, default is Z=up, using pybullet.configureDebugVisualizer(COV_ENABLE_Y_AXIS_UP,0/1)

Implement pybullet.getConnectionInfo, returns [isConnected, connectionMethod], where isConnected=0 or 1
This commit is contained in:
erwincoumans
2017-10-05 09:02:33 -07:00
parent f467f325f7
commit 9303891468
4 changed files with 55 additions and 8 deletions

View File

@@ -377,6 +377,13 @@ void OpenGLExampleBrowser::registerFileImporter(const char* extension, CommonExa
void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
{
if (flag == COV_ENABLE_Y_AXIS_UP)
{
//either Y = up or Z
int upAxis = enable? 1:2;
s_app->setUpAxis(upAxis);
}
if (flag == COV_ENABLE_RENDERING)
{
gEnableRenderLoop = (enable!=0);