mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
fix blocking plot.show() never terminating properly
This commit is contained in:
parent
cb23e6c102
commit
8750d49082
@ -1,5 +1,6 @@
|
||||
import pybullet as bullet
|
||||
plot = True
|
||||
import time
|
||||
|
||||
if (plot):
|
||||
import matplotlib.pyplot as plt
|
||||
@ -141,7 +142,10 @@ if plot:
|
||||
ax_tor.plot(t, q_tor[1], '-b', lw=2, label='Torque q1')
|
||||
ax_tor.set_ylim(-20., 20.)
|
||||
ax_tor.legend()
|
||||
|
||||
plt.show()
|
||||
|
||||
|
||||
plt.pause(0.01)
|
||||
|
||||
|
||||
while (1):
|
||||
bullet.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
|
2
setup.py
2
setup.py
@ -441,7 +441,7 @@ print("-----")
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='1.5.7',
|
||||
version='1.5.8',
|
||||
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',
|
||||
|
Loading…
Reference in New Issue
Block a user