summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <ecoumans@nvidia.com>2022-04-24 16:12:40 -0700
committerErwin Coumans <ecoumans@nvidia.com>2022-04-24 16:12:40 -0700
commita3ec1659157ed25237f2187d8f67e1ed91dc27ac (patch)
treea6791a8b74f3523359728815f0816ca8de88fcc9
parentd3b4c27db4f86e1853ff7d84185237c437dc8485 (diff)
downloadbullet3-a3ec1659157ed25237f2187d8f67e1ed91dc27ac.tar.gz
remove the 'override' keyword, Bullet is C++2003
-rw-r--r--examples/SharedMemory/PhysicsServerExample.cpp2
-rw-r--r--examples/pybullet/examples/profileTiming.py6
-rw-r--r--examples/pybullet/gym/pybullet_robots/panda/panda_sim.py1
3 files changed, 6 insertions, 3 deletions
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)]