Merge branch 'bulletphysics:master' into master

This commit is contained in:
Wenhao Yu
2021-10-13 15:53:04 -07:00
committed by GitHub
12 changed files with 65 additions and 37 deletions

View File

@@ -1 +1 @@
3.19
3.20

View File

@@ -7,6 +7,8 @@ import pybullet_data
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetDebugVisualizerCamera(cameraDistance=1.1, cameraYaw = 3.6,cameraPitch=-27, cameraTargetPosition=[0.19,1.21,-0.44])
p.loadURDF("plane.urdf", 0, 0, -2)
wheelA = p.loadURDF("differential/diff_ring.urdf", [0, 0, 0])
for i in range(p.getNumJoints(wheelA)):
@@ -21,7 +23,7 @@ c = p.createConstraint(wheelA,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=1, maxForce=10000)
p.changeConstraint(c, gearRatio=1, maxForce=10000,erp=0.2)
c = p.createConstraint(wheelA,
2,
@@ -31,7 +33,7 @@ c = p.createConstraint(wheelA,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=-1, maxForce=10000)
p.changeConstraint(c, gearRatio=-1, maxForce=10000,erp=0.2)
c = p.createConstraint(wheelA,
1,
@@ -41,7 +43,7 @@ c = p.createConstraint(wheelA,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=-1, maxForce=10000)
p.changeConstraint(c, gearRatio=-1, maxForce=10000,erp=0.2)
p.setRealTimeSimulation(1)
while (1):

View File

@@ -13,10 +13,28 @@ def test(args):
count = 0
env = gym.make(args.env)
env.env.configure(args)
print("args.render=", args.render)
if (args.render == 1):
env.render(mode="human")
env.reset()
w, h, vmat,projmat,camup,camfwd,hor,ver,yaw,pitch,dist,target= p.getDebugVisualizerCamera()
dist = 0.4
yaw = 0
p.resetDebugVisualizerCamera(dist,yaw, pitch,target)
for obindex in range (p.getNumBodies()):
obuid = p.getBodyUniqueId(obindex)
p.changeDynamics(obuid, -1, linearDamping=0, angularDamping=0)
for l in range (p.getNumJoints(obuid)):
p.changeDynamics(obuid, l, linearDamping=0, angularDamping=0, jointDamping=0)
#if (l==0):
# p.setJointMotorControl2(obuid,l,p.POSITION_CONTROL,targetPosition=0)
if (l==2):
jp,jv,_,_ = p.getJointState(obuid,l)
p.resetJointState(obuid,l, jp,0.01 )
if (args.resetbenchmark):
while (1):
env.reset()
@@ -26,6 +44,8 @@ def test(args):
print("action space:")
sample = env.action_space.sample()
action = sample * 0.0
action = [0,0]#sample * 0.0
print("action=")
print(action)
for i in range(args.steps):

View File

@@ -9,7 +9,6 @@ The following two environments are used in the RSS paper "[Sim-to-Real: Learning
The rest are experimental environments.
## Prerequisites
Install [TensorFlow](https://www.tensorflow.org/install/)
Install OpenAI gym
```

View File

@@ -18,8 +18,8 @@ os.sys.path.insert(0, parentdir)
import datetime
import os
import time
import logging
import tensorflow.compat.v1 as tf
from pybullet_envs.minitaur.envs import minitaur_logging_pb2
NUM_MOTORS = 8
@@ -74,7 +74,7 @@ def update_episode_proto(episode_proto, minitaur, action, step):
"""
max_num_steps = len(episode_proto.state_action)
if step >= max_num_steps:
tf.logging.warning("{}th step is not recorded in the logging since only {} steps were "
logging.warning("{}th step is not recorded in the logging since only {} steps were "
"pre-allocated.".format(step, max_num_steps))
return
step_log = episode_proto.state_action[step]
@@ -119,12 +119,13 @@ class MinitaurLogging(object):
"""
if not self._log_path or not episode_proto.state_action:
return self._log_path
if not tf.gfile.Exists(self._log_path):
tf.gfile.MakeDirs(self._log_path)
if not os.path.exists(self._log_path):
os.mkdir(self._log_path)
ts = time.time()
time_stamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H%M%S")
log_path = os.path.join(self._log_path, "minitaur_log_{}".format(time_stamp))
with tf.gfile.Open(log_path, "w") as f:
with open(log_path, 'wb') as f:
f.write(episode_proto.SerializeToString())
return log_path
@@ -136,7 +137,7 @@ class MinitaurLogging(object):
Returns:
The minitaur episode proto.
"""
with tf.gfile.Open(log_path, 'rb') as f:
with open(log_path, 'rb') as f:
content = f.read()
episode_proto = minitaur_logging_pb2.MinitaurEpisode()
episode_proto.ParseFromString(content)

View File

@@ -20,7 +20,8 @@ from __future__ import print_function
import os
import gin
import tensorflow.compat.v1 as tf
import sys
from pybullet_envs.minitaur.envs_v2 import env_loader
import pybullet_data as pd
@@ -81,4 +82,5 @@ def main(argv):
if __name__ == "__main__":
tf.app.run(main)
main(sys.argv)

View File

@@ -6,12 +6,12 @@ from __future__ import print_function
import gin
from pybullet_envs.minitaur.envs_v2 import locomotion_gym_config
import tensorflow.compat.v1 as tf
import unittest
from absl.testing import parameterized
class LocomotionGymConfigTest(tf.test.TestCase, parameterized.TestCase):
class LocomotionGymConfigTest(unittest.TestCase):
def testSimulationParametersFromGinString(self):
config_text = (
@@ -72,4 +72,4 @@ class LocomotionGymConfigTest(tf.test.TestCase, parameterized.TestCase):
if __name__ == '__main__':
tf.test.main()
unittest.main()

View File

@@ -10,7 +10,7 @@ import random
import gin
import mock
import numpy as np
import tensorflow.compat.v1 as tf
import unittest
from absl.testing import parameterized
from pybullet_envs.minitaur.envs_v2 import locomotion_gym_env
@@ -56,7 +56,7 @@ class TestTask(task_interface.Task):
return False
class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
class LocomotionGymEnvTest(unittest.TestCase):
def setUp(self):
super().setUp()
@@ -68,7 +68,7 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
env = locomotion_gym_env.LocomotionGymEnv()
self.assertIsInstance(env.robot, minitaur_v2.Minitaur)
# The robot will stand on the ground.
self.assertNear(env.robot.base_position[2], 0.25, 5e-2)
self.assertAlmostEqual(env.robot.base_position[2], 0.25, 1)
def test_reset_gym(self):
gin.parse_config_file(_CONFIG_FILE)
@@ -80,8 +80,8 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
action_dim)
observations = env_utils.flatten_observations(observations)
self.assertEqual(observations.size, 12)
self.assertNear(observations[0], 0, 1e-2)
self.assertNear(observations[4], desired_init_motor_angle, 2e-1)
self.assertAlmostEqual(observations[0], 0, 1)
self.assertAlmostEqual(observations[4], desired_init_motor_angle, 0)
def test_step_gym(self):
gin.parse_config_file(_CONFIG_FILE)
@@ -98,8 +98,8 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
self.assertFalse(done)
self.assertEqual(reward, steps)
self.assertEqual(observations.size, 12)
self.assertNear(observations[0], 0, 1e-2)
self.assertNear(observations[4], desired_motor_angle, 2e-1)
self.assertAlmostEqual(observations[0], 0, 1)
self.assertAlmostEqual(observations[4], desired_motor_angle, 1)
np.testing.assert_allclose(env._last_action,
[desired_motor_angle] * action_dim, 2e-1)
@@ -126,7 +126,7 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
env = locomotion_gym_env.LocomotionGymEnv(task=None, scene=None)
# The robot will free fall.
self.assertNear(env.robot.base_position[2], 0.15, 5e-2)
self.assertAlmostEqual(env.robot.base_position[2], 0.15, 1)
def test_seed_draw_with_np(self):
gin.parse_config_file(_CONFIG_FILE)
@@ -150,12 +150,11 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
action_dim = len(env.action_space.high)
observations = env.reset(initial_motor_angles=[desired_init_motor_angle] *
action_dim)
self.assertLen(observations, 2)
self.assertLen(observations['IMU'], 4)
self.assertNear(observations['IMU'][0], 0, 1e-2)
self.assertLen(observations['MotorAngle'], 8)
self.assertNear(observations['MotorAngle'][0], desired_init_motor_angle,
2e-1)
self.assertEqual(len(observations), 2)
self.assertEqual(len(observations['IMU']), 4)
self.assertAlmostEqual(observations['IMU'][0], 0, 2)
self.assertEqual(len(observations['MotorAngle']), 8)
self.assertAlmostEqual(observations['MotorAngle'][0], desired_init_motor_angle,0)
@@ -171,7 +170,7 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
])
env = locomotion_gym_env.LocomotionGymEnv()
self.assertLen(env.scene.dynamic_objects, 2)
self.assertEqual(len(env.scene.dynamic_objects), 2)
for obj in env.scene.dynamic_objects:
self.assertIsInstance(obj, autonomous_object.AutonomousObject)
@@ -238,4 +237,4 @@ class LocomotionGymEnvTest(tf.test.TestCase, parameterized.TestCase):
if __name__ == '__main__':
tf.test.main()
unittest.main()

View File

@@ -8,8 +8,13 @@ import collections
import gin
from gym import spaces
import numpy as np
import traceback
import logging
import tensorflow.compat.v1 as tf
try:
import tensorflow.compat.v1 as tf
except Exception as e:
pass # logging.warning(traceback.format_exc())

View File

@@ -501,7 +501,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup(
name='pybullet',
version='3.1.9',
version='3.2.0',
description=
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description=

View File

@@ -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 319
#define BT_BULLET_VERSION 320
inline int btGetVersion()
{

View File

@@ -480,8 +480,8 @@ public:
}
buffer[9] = '3';
buffer[10] = '1';
buffer[11] = '9';
buffer[10] = '2';
buffer[11] = '0';
}
virtual void startSerialization()