diff options
author | erwincoumans <erwin.coumans@gmail.com> | 2022-04-24 16:50:07 -0700 |
---|---|---|
committer | GitHub <noreply@github.com> | 2022-04-24 16:50:07 -0700 |
commit | e95657f80fcaccf2c83db3166d845c59d2cd2d2d (patch) | |
tree | 8625ee9412e83e4d9cefc379fcfbe32be207f4e4 | |
parent | 617df44898fe4cfbecd280604d2722e882215e18 (diff) | |
parent | 9eb945b1e846cf2a3d074ec4c2625dd0b4fc9875 (diff) | |
download | bullet3-e95657f80fcaccf2c83db3166d845c59d2cd2d2d.tar.gz |
Merge pull request #4251 from erwincoumans/master3.23
remove 'override' since Bullet uses C++2003
-rw-r--r-- | VERSION | 2 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsServerExample.cpp | 2 | ||||
-rw-r--r-- | examples/pybullet/examples/profileTiming.py | 6 | ||||
-rw-r--r-- | examples/pybullet/gym/pybullet_robots/panda/panda_sim.py | 1 | ||||
-rw-r--r-- | setup.py | 2 | ||||
-rw-r--r-- | src/LinearMath/btScalar.h | 2 | ||||
-rw-r--r-- | src/LinearMath/btSerializer.h | 2 |
7 files changed, 10 insertions, 7 deletions
@@ -1 +1 @@ -3.22 +3.23 diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 3e11b30b4..2d2416c8e 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -655,7 +655,7 @@ public: return m_debugMode; } - virtual void clearLines() override + virtual void clearLines() { m_hashedLines.clear(); m_sortedIndices.clear(); diff --git a/examples/pybullet/examples/profileTiming.py b/examples/pybullet/examples/profileTiming.py index 96c25b300..88e987df3 100644 --- a/examples/pybullet/examples/profileTiming.py +++ b/examples/pybullet/examples/profileTiming.py @@ -5,13 +5,15 @@ import time import pybullet_data p.connect(p.GUI) +#p.configureDebugVisualizer(p.ENABLE_RENDERING,0) +p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1) p.setAdditionalSearchPath(pybullet_data.getDataPath()) t = time.time() + 3.1 -logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json") +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "single_step_no_stepsim_chrome_about_tracing.json") while (time.time() < t): - p.stepSimulation() + #p.stepSimulation() p.submitProfileTiming("pythontest") time.sleep(1./240.) p.submitProfileTiming("nested") diff --git a/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py b/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py index b4d688687..006974b5d 100644 --- a/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py +++ b/examples/pybullet/gym/pybullet_robots/panda/panda_sim.py @@ -53,6 +53,7 @@ class PandaSim(object): pass def step(self): + self.bullet_client.getCameraImage(320,200) t = self.t self.t += 1./60. pos = [self.offset[0]+0.2 * math.sin(1.5 * t), self.offset[1]+0.044, self.offset[2]+-0.6 + 0.1 * math.cos(1.5 * t)] @@ -505,7 +505,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS: setup( name='pybullet', - version='3.2.2', + version='3.2.3', description= 'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description= diff --git a/src/LinearMath/btScalar.h b/src/LinearMath/btScalar.h index 837696ced..e27b71594 100644 --- a/src/LinearMath/btScalar.h +++ b/src/LinearMath/btScalar.h @@ -25,7 +25,7 @@ subject to the following restrictions: #include <float.h> /* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/ -#define BT_BULLET_VERSION 322 +#define BT_BULLET_VERSION 323 inline int btGetVersion() { diff --git a/src/LinearMath/btSerializer.h b/src/LinearMath/btSerializer.h index cf0f53c55..9c5525fb9 100644 --- a/src/LinearMath/btSerializer.h +++ b/src/LinearMath/btSerializer.h @@ -481,7 +481,7 @@ public: buffer[9] = '3'; buffer[10] = '2'; - buffer[11] = '2'; + buffer[11] = '3'; } virtual void startSerialization() |