From 91d164d88638d290e47c90519a34db4a06b75ca3 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 9 Oct 2017 09:44:54 -0700 Subject: [PATCH] remove obsolete CartPoleBulletEnv --- data/multibody.bullet | Bin 14844 -> 14844 bytes .../pybullet/gym/pybullet_envs/__init__.py | 7 -- .../gym/pybullet_envs/bullet/__init__.py | 1 - .../pybullet_envs/bullet/cartpole_bullet.py | 101 ------------------ setup.py | 2 +- 5 files changed, 1 insertion(+), 110 deletions(-) delete mode 100644 examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py diff --git a/data/multibody.bullet b/data/multibody.bullet index e57061f7ae941a64931368b8fc823d88f3592bad..ebec1dad39795e8d109a00d09b277549fc337556 100644 GIT binary patch delta 392 zcmexU{HJ)r7FI3>1_tiQ6Im=LeyS4Vx~^;kRE8fT|f7KuZ4ufdoiB5P;Yqz`07{!0CJydyxZ< z`$6LA7C-mL#Z0%4mJr+v;(xf3{)2I{BC|FhGmrhmjD0& delta 404 zcmexU{HJ)rmdPTVHWNS8_zO6MZQ54P00RL~Mu0E_M4SgI-~dy>1Y>~dfNWXS?BDDR z7g!kzfG}tBZbs?J{~2Y3I2a-d`4;|1GI{bxMv2KXOe)$SjSgVlKmye`283}z4519J zKs~aP=P+_itl^r(B*n@M)W8fBlbpPdg=6w9CMk6s=Ab#Ncyc4FxsfVEgCoRK6Hq

L7kyAIX^cyF)wB6Q3nOqNenzdtHebEQlr6MoWKrN1tBJHU{*0LaDo`e0+n!p pDS&$FTnbntgF!NgHh_f4iS?8Cyr%)!9AIh- diff --git a/examples/pybullet/gym/pybullet_envs/__init__.py b/examples/pybullet/gym/pybullet_envs/__init__.py index 93b55108d..74b9b7c9b 100644 --- a/examples/pybullet/gym/pybullet_envs/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/__init__.py @@ -2,13 +2,6 @@ from gym.envs.registration import registry, register, make, spec # ------------bullet------------- -register( - id='CartPoleBulletEnv-v0', - entry_point='pybullet_envs.bullet:CartPoleBulletEnv', - timestep_limit=1000, - reward_threshold=950.0, -) - register( id='MinitaurBulletEnv-v0', entry_point='pybullet_envs.bullet:MinitaurBulletEnv', diff --git a/examples/pybullet/gym/pybullet_envs/bullet/__init__.py b/examples/pybullet/gym/pybullet_envs/bullet/__init__.py index 8b1735fb1..682266d85 100644 --- a/examples/pybullet/gym/pybullet_envs/bullet/__init__.py +++ b/examples/pybullet/gym/pybullet_envs/bullet/__init__.py @@ -1,4 +1,3 @@ -from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv from pybullet_envs.bullet.minitaur_gym_env import MinitaurBulletEnv from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv diff --git a/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py b/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py deleted file mode 100644 index e28a9e962..000000000 --- a/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py +++ /dev/null @@ -1,101 +0,0 @@ -""" -Classic cart-pole system implemented by Rich Sutton et al. -Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c -""" -import os, inspect -currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe()))) -parentdir = os.path.dirname(os.path.dirname(currentdir)) -os.sys.path.insert(0,parentdir) - -import logging -import math -import gym -from gym import spaces -from gym.utils import seeding -import numpy as np -import time -import subprocess -import pybullet as p -import pybullet_data - - -logger = logging.getLogger(__name__) - -class CartPoleBulletEnv(gym.Env): - metadata = { - 'render.modes': ['human', 'rgb_array'], - 'video.frames_per_second' : 50 - } - - def __init__(self, renders=True): - # start the bullet physics server - self._renders = renders - if (renders): - p.connect(p.GUI) - else: - p.connect(p.DIRECT) - - observation_high = np.array([ - np.finfo(np.float32).max, - np.finfo(np.float32).max, - np.finfo(np.float32).max, - np.finfo(np.float32).max]) - action_high = np.array([0.1]) - - self.action_space = spaces.Discrete(9) - self.observation_space = spaces.Box(-observation_high, observation_high) - - self.theta_threshold_radians = 1 - self.x_threshold = 2.4 - self._seed() -# self.reset() - self.viewer = None - self._configure() - - def _configure(self, display=None): - self.display = display - - def _seed(self, seed=None): - self.np_random, seed = seeding.np_random(seed) - return [seed] - - def _step(self, action): - p.stepSimulation() -# time.sleep(self.timeStep) - self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2] - theta, theta_dot, x, x_dot = self.state - - dv = 0.1 - deltav = [-10.*dv,-5.*dv, -2.*dv, -0.1*dv, 0, 0.1*dv, 2.*dv,5.*dv, 10.*dv][action] - - p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, targetVelocity=(deltav + self.state[3])) - - done = x < -self.x_threshold \ - or x > self.x_threshold \ - or theta < -self.theta_threshold_radians \ - or theta > self.theta_threshold_radians - reward = 1.0 - - return np.array(self.state), reward, done, {} - - def _reset(self): -# print("-----------reset simulation---------------") - p.resetSimulation() - self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0]) - self.timeStep = 0.01 - p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0) - p.setGravity(0,0, -10) - p.setTimeStep(self.timeStep) - p.setRealTimeSimulation(0) - - initialCartPos = self.np_random.uniform(low=-0.5, high=0.5, size=(1,)) - initialAngle = self.np_random.uniform(low=-0.5, high=0.5, size=(1,)) - p.resetJointState(self.cartpole, 1, initialAngle) - p.resetJointState(self.cartpole, 0, initialCartPos) - - self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2] - - return np.array(self.state) - - def _render(self, mode='human', close=False): - return diff --git a/setup.py b/setup.py index 0321e9658..612404491 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.5.1', + version='1.5.5', 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',