Merge pull request #1879 from erwincoumans/master

fix internal build / pybullet version bump
This commit is contained in:
erwincoumans 2018-09-14 18:54:41 -07:00 committed by GitHub
commit d315673d3a
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 19 additions and 33 deletions

View File

@ -390,6 +390,13 @@ void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
{
gEnableRenderLoop = (enable!=0);
}
if (flag == COV_ENABLE_SINGLE_STEP_RENDERING)
{
singleStepSimulation = true;
}
if (flag == COV_ENABLE_SHADOWS)
{
useShadowMap = enable;

View File

@ -6,11 +6,7 @@
#include<stdio.h>
#include<stdlib.h>
#ifdef GLEW_STATIC
#include "glad/gl.h"
#else
#include <GL/glew.h>
#endif//GLEW_STATIC
#ifdef GLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS
#include "glad/glx.h"

View File

@ -1824,6 +1824,8 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH
guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
} else
{
//state loggers use guiHelper, so remove them before the guiHelper is deleted
deleteStateLoggers();
if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer())
{

View File

@ -793,7 +793,7 @@ enum b3ConfigureDebugVisualizerEnum
COV_ENABLE_DEPTH_BUFFER_PREVIEW,
COV_ENABLE_SEGMENTATION_MARK_PREVIEW,
COV_ENABLE_PLANAR_REFLECTION,
COV_ENABLE_SINGLE_STEP_RENDERING,
};
enum b3AddUserDebugItemEnum

View File

@ -28,7 +28,7 @@ typedef SharedMemoryCommandProcessor MyCommandProcessor;
#include <grpc++/grpc++.h>
#include <grpc/support/log.h>
#include "proto/pybullet.grpc.pb.h"
#include "SharedMemory/grpc/proto/pybullet.grpc.pb.h"
using grpc::Server;

View File

@ -14,4 +14,5 @@ p.setCollisionFilterPair(planeId, cubeId,-1,-1,enableCollision )
p.setRealTimeSimulation(1)
p.setGravity(0,0,-10)
while (p.isConnected()):
time.sleep(1)
time.sleep(1./240.)
p.setGravity(0,0,-10)

View File

@ -1,21 +0,0 @@
import pybullet as p
import time
import math
import sys
sys.path.append(".")
from minitaur import Minitaur
p.connect(p.GUI)
p.setTimeOut(5)
#p.setPhysicsEngineParameter(numSolverIterations=50)
p.setGravity(0,0,-10)
p.setTimeStep(0.01)
urdfRoot = ''
p.loadURDF("%s/plane.urdf" % urdfRoot)
minitaur = Minitaur(urdfRoot)
while (True):
p.stepSimulation()
time.sleep(0.01)

View File

@ -9815,6 +9815,7 @@ initpybullet(void)
PyModule_AddIntConstant(m, "COV_ENABLE_DEPTH_BUFFER_PREVIEW", COV_ENABLE_DEPTH_BUFFER_PREVIEW);
PyModule_AddIntConstant(m, "COV_ENABLE_SEGMENTATION_MARK_PREVIEW", COV_ENABLE_SEGMENTATION_MARK_PREVIEW);
PyModule_AddIntConstant(m, "COV_ENABLE_PLANAR_REFLECTION", COV_ENABLE_PLANAR_REFLECTION);
PyModule_AddIntConstant(m, "COV_ENABLE_SINGLE_STEP_RENDERING", COV_ENABLE_SINGLE_STEP_RENDERING);
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);

View File

@ -42,7 +42,6 @@ CXX_FLAGS += '-DBT_USE_DOUBLE_PRECISION '
CXX_FLAGS += '-DBT_ENABLE_ENET '
CXX_FLAGS += '-DBT_ENABLE_CLSOCKET '
CXX_FLAGS += '-DB3_DUMP_PYTHON_VERSION '
CXX_FLAGS += '-DBT_USE_EGL '
EGL_CXX_FLAGS = ''
@ -451,6 +450,10 @@ egl_renderer_sources = \
+["examples/OpenGLWindow/LoadShader.cpp"] \
+["src/LinearMath/btQuickprof.cpp"]
if 'BT_USE_EGL' in CXX_FLAGS:
sources += ['examples/ThirdPartyLibs/glad/egl.c']
sources += ['examples/OpenGLWindow/EGLOpenGLWindow.cpp']
if _platform == "linux" or _platform == "linux2":
libraries = ['dl','pthread']
CXX_FLAGS += '-D_LINUX '
@ -468,9 +471,6 @@ if _platform == "linux" or _platform == "linux2":
+["examples/ThirdPartyLibs/glad/gl.c"]\
+["examples/ThirdPartyLibs/glad/glx.c"]
include_dirs += ["examples/ThirdPartyLibs/optionalX11"]
if 'BT_USE_EGL' in CXX_FLAGS:
sources += ['examples/ThirdPartyLibs/glad/egl.c']
sources += ['examples/OpenGLWindow/EGLOpenGLWindow.cpp']
if 'BT_USE_EGL' in EGL_CXX_FLAGS:
egl_renderer_sources = egl_renderer_sources\
@ -545,7 +545,7 @@ eglRender = Extension("eglRenderer",
setup(
name = 'pybullet',
version='2.1.5',
version='2.1.6',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',