Giter Site home page Giter Site logo

benelot / pybullet-gym Goto Github PK

View Code? Open in Web Editor NEW
813.0 10.0 122.0 19.31 MB

Open-source implementations of OpenAI Gym MuJoCo environments for use with the OpenAI Gym Reinforcement Learning Research Platform.

Home Page: https://pybullet.org/

License: Other

Python 100.00%
python openai-gym pybullet

pybullet-gym's Introduction

PyBullet Gymperium

PyBullet Gymperium is an open-source implementation of the OpenAI Gym MuJoCo environments for use with the OpenAI Gym Reinforcement Learning Research Platform in support of open research.

OpenAI gym is currently one of the most widely used toolkit for developing and comparing reinforcement learning algorithms. Unfortunately, for several challenging continuous control environments it requires the user to install MuJoCo, a commercial physics engine which requires a license to run for longer than 30 days. Such a commercial barrier hinders open research, especially in the perspective that other appropriate physics engines exist. This repository provides alternative implementations of the original MuJoCo environments which can be used for free. The environments have been reimplemented using BulletPhysics' python wrapper pybullet, such that they seamlessly integrate into the OpenAI gym framework. In order to show the usability of the new environments, several RL agents from the Tensorforce Reinforcement Learning Library are configured to be trainable out of the box. To simplify research with the implemented environment, each environment is featured with pretrained agents which serve as unit tests for the implementations and could well serve as baselines for other purposes.

If you find our work useful in your research please consider citing as follows:

@misc {benelot2018, author = {Benjamin Ellenberger}, title = {PyBullet Gymperium}, howpublished = {\url{ https://github.com/benelot/pybullet-gym}} , year = {2018--2019} }

State of implementations

Environment Name Implemented Similar to Reference Implementation Pretrained agent available
RoboSchool Envs
InvertedPendulumPyBulletEnv-v0 Yes Yes No
InvertedDoublePendulumPyBulletEnv-v0 Yes Yes No
InvertedPendulumSwingupPyBulletEnv-v0 Yes Yes No
ReacherPyBulletEnv-v0 Yes Yes No
Walker2DPyBulletEnv-v0 Yes No No
HalfCheetahPyBulletEnv-v0 Yes No No
AntPyBulletEnv-v0 Yes Yes No
HopperPyBulletEnv-v0 Yes Yes No
HumanoidPyBulletEnv-v0 Yes Yes No
HumanoidFlagrunPyBulletEnv-v0 Yes Yes No
HumanoidFlagrunHarderPyBulletEnv-v0 Yes Yes No
AtlasPyBulletEnv-v0 WIP No No
PusherPyBulletEnv-v0 WIP No No
ThrowerPyBulletEnv-v0 WIP No No
StrikerPyBulletEnv-v0 WIP No No
MuJoCo Envs
InvertedPendulumMuJoCoEnv-v0 Yes Yes Yes
InvertedDoublePendulumMuJoCoEnv-v0 Yes Yes Yes
ReacherMuJoCoEnv-v0 No No No
Walker2DMuJoCoEnv-v0 Yes No No
HalfCheetahMuJoCoEnv-v0 Yes No No
AntMuJoCoEnv-v0 Yes No No
HopperMuJoCoEnv-v0 Yes No No
HumanoidMuJoCoEnv-v0 Yes No No
PusherMuJoCoEnv-v0 No No No
ThrowerMuJoCoEnv-v0 No No No
StrikerMuJoCoEnv-v0 No No No

[See What's New section below](#What's New)

Basics

(taken from OpenAI gym readme)

There are two basic concepts in reinforcement learning: the environment (namely, the outside world) and the agent (namely, the algorithm you are writing). The agent sends actions to the environment, and the environment replies with observations and rewards (that is, a score).

The core gym interface is Env <https://github.com/openai/gym/blob/master/gym/core.py>_, which is the unified environment interface. There is no interface for agents; that part is left to you. The following are the Env methods you should know:

  • reset(self): Reset the environment's state. Returns observation.
  • step(self, action): Step the environment by one timestep. Returns observation, reward, done, info.
  • render(self, mode='human', close=False): Render one frame of the environment. The default mode will do something human friendly, such as pop up a window. Passing the close flag signals the renderer to close any such windows.

In addition to the basic concepts of reinforcement learning, this framework extends the notion of an environment into two subconcepts being the robot (the agents directly controllable body) and the scene (all things the agents interacts with). Implementing RL environments in this way allows us to switch parts of the environment to generate new robot-scene combinations.

Installing Pybullet-Gym

First, you can perform a minimal installation of OpenAI Gym with

git clone https://github.com/openai/gym.git
cd gym
pip install -e .

Then, the easiest way to install Pybullet-Gym is to clone the repository and install locally

git clone https://github.com/benelot/pybullet-gym.git
cd pybullet-gym
pip install -e .

Important Note: Do not use python setup.py install as this will not copy the assets (you might get missing SDF file errors).

Finally, to test installation, open python and run

import gym  # open ai gym
import pybulletgym  # register PyBullet enviroments with open ai gym

env = gym.make('HumanoidPyBulletEnv-v0')
# env.render() # call this before env.reset, if you want a window showing the environment
env.reset()  # should return a state vector if everything worked

Supported systems

We currently support Linux, Windows and OS X running Python 2.7 or 3.5.

To run pip install -e '.[all]', you'll need a semi-recent pip. Please make sure your pip is at least at version 1.5.0. You can upgrade using the following: pip install --ignore-installed pip. Alternatively, you can open setup.py <https://github.com/openai/gym/blob/master/setup.py>_ and install the dependencies by hand.

Agents

As some sort of unit test for the environments, we provide pretrained agents for each environment. The agents for the roboschool envs and the mujoco were trained on the original implementations of roboschool and mujoco respectively.

Environments

The code for each environment group is housed in its own subdirectory gym/envs <https://github.com/openai/gym/blob/master/gym/envs>. The specification of each task is in gym/envs/__init__.py <https://github.com/openai/gym/blob/master/gym/envs/__init__.py>. It's worth browsing through both.

What's new

  • 2018-01-09 Pybullet-gym is born.

Roadmap

  1. [ROBOSCHOOL GYMS] The current gyms are the roboschool gyms ported to pybullet. So far, most of them work well, except for the manipulator envs striker, pusher and thrower, where the robot is not correctly loaded. This will have to be fixed with Erwin Coumans.
  2. [OPENAI MUJOCO GYMS] Soon I will start to port the OpenAI gyms, which unfortunately have a slightly different observation (and probably action) vector. I can setup all the gyms quickly, but it will take a while to find out what some of observations are in mujoco and what they correspond to in pybullet. Some of the observations might not be exposed on pybullet, then we can request them, for others it is already hard to know what they are in mujoco.
  3. [OPENAI ROBOTICS GYMS] Next in line would be the robotics gyms in OpenAI. These are particularly delicate simulations and might take some tuning to even be simulatable in pybullet.
  4. [DEEPMIND CONTROL SUITE] Then there is Deepmind Control Suite, another set of gyms which are in mujoco and need to be freed.

pybullet-gym's People

Contributors

benelot avatar forcecore avatar gabrielhuang avatar giarcieri avatar gromgull avatar hiwonjoon avatar isacarnekvist avatar jonathanraiman avatar lgvaz avatar ottpeterr avatar seolhokim avatar traversaro avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

pybullet-gym's Issues

pybullet-gym is incompatible with pybullet 2.6.0

Installing pybullet-gym as per instructions in the README fails on new conda environments due to incompatibility with pybullet 2.6.0. Attempting to create an env by

import gym, pybulletgym
env = gym.make('HumanoidPyBulletEnv-v0')

results in this error:

pybullet build time: Dec 18 2019 12:54:45
current_dir=/home/harry/anaconda3/envs/temp_test_2/lib/python3.6/site-packages/pybullet_envs/bullet
---------------------------------------------------------------------------
ImportError                               Traceback (most recent call last)
<ipython-input-3-fe077ecabe6a> in <module>
----> 1 env = gym.make('HumanoidPyBulletEnv-v0')

~/anaconda3/envs/temp_test_2/lib/python3.6/site-packages/gym/envs/registration.py in make(id, **kwargs)
    154 
    155 def make(id, **kwargs):
--> 156     return registry.make(id, **kwargs)
    157 
    158 def spec(id):

~/anaconda3/envs/temp_test_2/lib/python3.6/site-packages/gym/envs/registration.py in make(self, path, **kwargs)
     99             logger.info('Making new env: %s', path)
    100         spec = self.spec(path)
--> 101         env = spec.make(**kwargs)
    102         # We used to have people override _reset/_step rather than
    103         # reset/step. Set _gym_disable_underscore_compat = True on

~/anaconda3/envs/temp_test_2/lib/python3.6/site-packages/gym/envs/registration.py in make(self, **kwargs)
     70             env = self.entry_point(**_kwargs)
     71         else:
---> 72             cls = load(self.entry_point)
     73             env = cls(**_kwargs)
     74 

~/anaconda3/envs/temp_test_2/lib/python3.6/site-packages/gym/envs/registration.py in load(name)
     15 def load(name):
     16     mod_name, attr_name = name.split(":")
---> 17     mod = importlib.import_module(mod_name)
     18     fn = getattr(mod, attr_name)
     19     return fn

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/__init__.py in import_module(name, package)
    124                 break
    125             level += 1
--> 126     return _bootstrap._gcd_import(name[level:], package, level)
    127 
    128 

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap.py in _gcd_import(name, package, level)

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap.py in _find_and_load(name, import_)

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap.py in _find_and_load_unlocked(name, import_)

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap.py in _load_unlocked(spec)

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap_external.py in exec_module(self, module)

~/anaconda3/envs/temp_test_2/lib/python3.6/importlib/_bootstrap.py in _call_with_frames_removed(f, *args, **kwds)

~/coding/pybullet-gym/pybulletgym/envs/roboschool/envs/locomotion/humanoid_env.py in <module>
----> 1 from pybulletgym.envs.roboschool.envs.locomotion.walker_base_env import WalkerBaseBulletEnv
      2 from pybulletgym.envs.roboschool.robots.locomotors import Humanoid
      3 
      4 
      5 class HumanoidBulletEnv(WalkerBaseBulletEnv):

~/coding/pybullet-gym/pybulletgym/envs/roboschool/envs/locomotion/walker_base_env.py in <module>
----> 1 from pybulletgym.envs.roboschool.envs.env_bases import BaseBulletEnv
      2 from pybulletgym.envs.roboschool.scenes import StadiumScene
      3 import pybullet
      4 import numpy as np
      5 

~/coding/pybullet-gym/pybulletgym/envs/roboschool/envs/env_bases.py in <module>
      2 import numpy as np
      3 import pybullet
----> 4 from pybullet_envs.bullet import bullet_client
      5 
      6 from pkg_resources import parse_version

ImportError: cannot import name 'bullet_client'

After some experimentation I discovered that downgrading pybullet using

pip install pybullet==2.5.6

fixes the issue. In pybullet 2.6.0 the bullet_client.py file is indeed completely absent.

On Windows, when testing agent, get "Cannot import name 'bullet_client' error

Seems to be version mismatch between latest pybullet-gym and pybullet 2.6.2. Which version of pybullet should be used with pybullet-gym?

When I run the example for testing MuJoCo humaniod agent, I get the following error:

**pybullet build time: Jan 2 2020 14:03:15
current_dir=c:\anaconda3\envs\bulletgym\lib\site-packages\pybullet_envs\bullet
Traceback (most recent call last):
File "./openai_gym.py", line 219, in
main()
File "./openai_gym.py", line 113, in main
visualize=args.visualize
File "c:\anaconda3\envs\bulletgym\lib\site-packages\tensorforce\contrib\openai_gym.py", line 50, in init
self.gym = gym.make(gym_id) # Might raise gym.error.UnregisteredEnv or gym.error.DeprecatedEnv
File "c:\github\gym\gym\envs\registration.py", line 142, in make
return registry.make(id, **kwargs)
File "c:\github\gym\gym\envs\registration.py", line 87, in make
env = spec.make(kwargs)
File "c:\github\gym\gym\envs\registration.py", line 58, in make
cls = load(self.entry_point)
File "c:\github\gym\gym\envs\registration.py", line 17, in load
mod = importlib.import_module(mod_name)
File "c:\anaconda3\envs\bulletgym\lib\importlib_init_.py", line 126, in import_module
return _bootstrap._gcd_import(name[level:], package, level)
File "", line 994, in _gcd_import
File "", line 971, in _find_and_load
File "", line 955, in _find_and_load_unlocked
File "", line 665, in _load_unlocked
File "", line 678, in exec_module
File "", line 219, in _call_with_frames_removed
File "c:\github\pybullet-gym\pybulletgym\envs\mujoco\envs\locomotion\humanoid_env.py", line 1, in
from pybulletgym.envs.mujoco.envs.locomotion.walker_base_env import WalkerBaseMuJoCoEnv
File "c:\github\pybullet-gym\pybulletgym\envs\mujoco\envs\locomotion\walker_base_env.py", line 1, in
from pybulletgym.envs.mujoco.envs.env_bases import BaseBulletEnv
File "c:\github\pybullet-gym\pybulletgym\envs\mujoco\envs\env_bases.py", line 4, in
from pybullet_envs.bullet import bullet_client
ImportError: cannot import name 'bullet_client'

Created bullet_client with id...

Every time we reset a environment that is a subclass from MJCFBasedRobot we get the message "Created bullet_client with id=0".

Am I doing something wrong? This message becomes annoying really fast.

Doesn't render anything

Hello,
I installed pybullet-gym by

git clone https://github.com/benelot/pybullet-gym.git
cd pybullet-gym 
pip install -e .

The environments are working and running fine (stepping and giving rewards).
But they don't render anything.
Is there something I'm missing ?

Thanks

Edit with additional info :
In my code I import pybullet-gym with

import gym
import pybulletgym.envs 
env = gym.make("InvertedDoublePendulumMuJoCoEnv-v0")
env.reset()
env.render("human")

Pre-trained agents

It would be good to provide some guidelines or any consideration that might be needed to provide some pre-trained agents. I need that for a project of mine and I can use some help regarding how the pre-trained agents should be produced, the format and loading and etc.

If you have any suggestion please share.

How to get the timestep of an environment?

Hello, my project needs to use the property timestep which is similar to the property env.env.dt in gym class control environments. I don't see a similar value in something like InvertedPendulumMuJoCoEnv-v0, how do I implement it? Thanks.

AntMuJoCoEnv-v0 contains many unnecessary states.

env = gym.make("AntMuJoCoEnv-v0")
env.reset()
for i in range(10):
    state,_,_,_ = env.step(env.action_space.sample())
print(state)
array([ 0.48600267, -0.02747473, -0.0488695 ,  0.55320414,  0.76180714,
       -0.46062074,  0.7321935 ,  0.43551934, -0.59654198,  0.01406484,
       -0.9421499 ,  0.35980088,  0.96942428,  0.34243858,  0.07390555,
       -0.01478774, -0.01189533,  0.00519861,  0.10619358, -0.02251298,
        0.04225551,  0.03821672, -0.03983905,  0.0030749 , -0.06877575,
        0.03366648,  0.06564061,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ,  0.        ,  0.        ,  0.        ,  0.        ,
        0.        ])

I think we can remove many states after a certain index, what do you think?

On Windows, latest pybullet-gym not compatible with latest tensorforce

On Windows 10, using new conda with python=3.6, installed latest tensorflow, tensorforce, openai gym, pybullet-gym. Trying to train humanoid with:

python ./openai_gym.py HumanoidPyBulletEnv-v0 -a ./configs/ppo.json -n ./configs/mlp2_network.json -e 1000000 -m 2000 -s ./checkpoints/mujoco-humanoidv0/humanoidv0 -D

Results in error:
Traceback (most recent call last):
File "./openai_gym.py", line 32, in
from tensorforce import TensorForceError
ImportError: cannot import name 'TensorForceError'

If I correct the import line to " from tensorforce import TensorforceError as TensorForceError", I then continue to get new errors.

Is there a specific version of Tensorforce that I should be using?

Add License

This seems like a great project! It's probaby worth adding a license. At least, I know I tend to feel happier about using software once it has a license :) There's info on licenses here, and pybullet uses zlib.

Why are there references to extra "non-existent" links?

I am using the 2D walker example but I notice this problem happens with other environments as well.

I am trying to change the instantaneous base velocity for a single link using:

env_instance.env._p.resetBaseVelocity(env_instance.env.robot.parts['thigh'].bodyPartIndex, linearVelocity = [0,0,0], angularVelocity=[0,0,0], physicsClientId = env_instance.env._p._client)

However when I type in the following:

import gym
import pybulletgym
env_instance = gym.make("Walker2DPyBulletEnv-v0", render=True)
env_instance.reset()
env_instance.env.robot.parts

The output gives a list of 17 links, but there should be about 8 max (including the floor):

{'link0_2': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc8e20438>, 'torso': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b710>, 'link0_3': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b5f8>, 'link0_4': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b6a0>, 'link0_6': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b780>, 'thigh': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b860>, 'link0_8': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b908>, 'leg': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657b9e8>, 'link0_10': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657ba58>, 'foot': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bb38>, 'link0_12': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bbe0>, 'thigh_left': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bba8>, 'link0_14': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bcc0>, 'leg_left': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bd68>, 'link0_16': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bdd8>, 'foot_left': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657be80>, 'floor': <pybulletgym.envs.roboschool.robots.robot_bases.BodyPart object at 0x7f1dc657bef0>}

pybullet build error on macos 10.15.5

After I upgraded to the latest macOS 10.15.5 pybullet stopped working for me. I am using conda version 4.8.3 and python 3.6. When attempting to reinstall, I get the following output (attached for readability, sorry for zip file, full log is 27MB and GitHub only allows 10MB attached). I have xcode command line tools installed, the brew gcc and brew doctor seems okay. Is someone experiencing a similar issue?

pybullet_output.txt.zip

cd pybullet-gym/
(bullet) MacBookPro:pybullet-gym christoph$ pip install -e .
Obtaining file:///Users/christoph/tum-adlr-ss20-03/pybullet-gym
Collecting pybullet>=1.7.8
  Using cached pybullet-2.8.1.tar.gz (83.0 MB)
Building wheels for collected packages: pybullet
  Building wheel for pybullet (setup.py) ... error
  ERROR: Command errored out with exit status 1:
   command: /Users/christoph/anaconda3/envs/bullet/bin/python -u -c 'import sys, setuptools, tokenize; sys.argv[0] = '"'"'/private/var/folders/2g/dhdj499j4v3bx4b16x0t68t00000gn/T/pip-install-4ocj117i/pybullet/setup.py'"'"'; __file__='"'"'/private/var/folders/2g/dhdj499j4v3bx4b16x0t68t00000gn/T/pip-install-4ocj117i/pybullet/setup.py'"'"';f=getattr(tokenize, '"'"'open'"'"', open)(__file__);code=f.read().replace('"'"'\r\n'"'"', '"'"'\n'"'"');f.close();exec(compile(code, __file__, '"'"'exec'"'"'))' bdist_wheel -d /private/var/folders/2g/dhdj499j4v3bx4b16x0t68t00000gn/T/pip-wheel-kzg94r0f
       cwd: /private/var/folders/2g/dhdj499j4v3bx4b16x0t68t00000gn/T/pip-install-4ocj117i/pybullet/

Issues Rendering Environments After Training

So, when I run a simple script such as
`import gym
import numpy as np
import pybulletgym.envs
import gym.envs

env = gym.make('HumanoidPyBulletEnv-v0')
env.render(mode='human')
done = False
state = env.reset()
for step in range(1000):
if done:
state = env.reset()
action = env.action_space.sample()
print(state.shape)
state, reward, done, info = env.step(action)
print(info)
env.render(mode='human')`

The environment renders and displays just fine, however when I train an agent then test it, the environment won't render. It doesn't crash, it just won't display for some odd reason. The function I use to display the agent is as follows
`def test(episodes=10):
for episode in range(episodes):
state = env.reset() # Reset environment and record the starting state
env.render(mode = 'human')
done = False

    while not done:
        action = select_action(state)
        # Step through environment using chosen action
        state, reward, done, _ = env.step(action.detach().numpy())
        env.render(mode='human')`

Thanks!

Missing pybullet-gym installation

How do you install pybulletgym?

I installed openai gym, and pybulletgym. But how do I add the environments you have there?

I have attempted pip install pybulletgym, and get nothing

Same seed different results

Hi,
If I set the seed, I get different results between different runs.

I am attaching a small script to reproduce the issue:

import gym
import pybullet
import pybulletgym

env = gym.make('AntMuJoCoEnv-v0')

env.seed(7)

obs = env.reset()
act = env.action_space.sample()
print(act)

obs = env.reset()
act = env.action_space.sample()
print(act)

The results I obtain are:

[ 0.36626342  0.64521587 -0.06823247  0.3184726   0.49362287  0.06656755
  0.8346416   0.71423185]
[-0.88181156 -0.4371754   0.45050308  0.7611305   0.27231112 -0.43260667
 -0.3026008  -0.3178519 ]

And they change among any run.

I think this is a bug, cause the result should be always the same, given the same seed.
Or am I doing something wrong?

Stopping render - relation between the simulation and rendering

Hello !

I just discovered your package. I would like to use it as a drop in replacement in my implementation but I am facing some issues regarding rendering.

My first question is naive but https://github.com/bulletphysics/bullet3/issues/2306 suggests that rendering and the actual physical state simulation are related. Let's say I want to use InvertedPendulumPyBulletEnv-v0. Will rendering change the way the physics is simulated ?

My second question follows the first one. I would like to render only at evaluation time. Is that a good idea ? It seems rendering is to be opened once for all and is not intended to be opened and closed many times.

Thank you in advance !

robot out of view when using env.render('rgb_array')

Hi,

Thanks for this repo ! I'm having issues with the robot not being tracked properly by the camera. As a test, I trained a HalfCheetah agent and I visualize the learned policy by deploying it in the environment and visualizing it using env.render('rgb_array'). While the camera starts off tracking the robot well, after a few timesteps, the robot moves out of the frame. This is what it looks like :

image

Support for saving/loading state

There are situations in which you would want to do a rollout from the current env state (say for estimating the return from that given state) and then continue from that point on. For mujoco envs you can do something along:

saved_state = env.sim.get_state()

# then on some other process or in a different routine
env.sim.set_state(saved_state)

I poked around the env object returned by gym.make() and there doesn't seem a way right now. Simply using deepcopy won't cut it. Any pointers towards how it could be implemented? I'd be willing to look into this.

The bulit-in texture doesn't load correctly

Hi all:
I just switch my system from ubuntu to windows, and I found that all of the built-in textures can't be loaded. I just run the demo scene in pybullet gym official examples, and clearly the "checker" wasn't loaded correctly.
Y7C003 ZSHF1R EV_JBGISQ
I checked the scene file in pybulletgym/envs/asset/mjcf/ground.xml, where it describes

<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>

So, am I seeking the wrong file, or are there any more packages needed to install to load the built-in textures?

OpenAI Gym Robotics environments implementation

Hey so I want to use some of the Fetch robot environments in OpenAI but, for some weird reason, they continue to use MuJoCo ๐Ÿ™„.

I was wondering if there is any work being done on adding the robotics environments?

If the answer to the above is no, I am willing to put in some time to get support for these environments. The only problem is, I am not 100% sure where to start, so any pointers would be nice.

Camera adjust not working

Calling env.env.camera_adjust()

results in undefined attribute self._p at following line :

self._p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)

In pybulletgym/envs/mujoco/env_bases.py
The fix is to inject the env into the camera with :
in init :

self.camera = Camera(self)

and then

class Camera:
	def __init__(self,env):
		self.env = env
		pass

	def move_and_look_at(self,i,j,k,x,y,z):
		lookat = [x,y,z]
		distance = 10
		yaw = 10
		self.env._p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)



Terminal state in inverted_pendulum_env.py

Thanks for the efforts in making this repo!

Looks like the code was trying to combine these two lines of code from the original OpenAI Gym:

code0:

notdone = np.isfinite(ob).all() and (np.abs(ob[1]) <= .2)
done = not notdone

into one line of code

code1:

done = not np.isfinite(state).all() or np.abs(state[1]) > .2

But if we follow the logic to convert code0 to code1-like version step by step, shouldn't it be:

notdone = np.isfinite(ob).all() and (np.abs(ob[1]) <= .2)
done = not notdone

=> step1

done = not np.isfinite(ob).all() and (np.abs(ob[1]) <= .2)

=> step2

done = not (np.isfinite(ob).all() and (np.abs(ob[1]) <= .2))

=> step3

done = (not np.isfinite(ob).all()) or (not np.abs(ob[1]) <= .2)

=> step4

code2:

done = (not np.isfinite(ob).all()) or (np.abs(ob[1]) > .2)

Note the difference between the precedences of bracket and 'not' in code1 and code2.

Update on Y2020M06D08Mon, code1 is equivalent to code2.

[Question] in URDFBasedRobot

Hello,
In the class URDFBasedRobot, don't you need a variable self.doneLoading as in MJCFBasedRobot in order not to spawn multiple robot when we reset the robot?
For example,

		if (self.doneLoading==0):
			self.ordered_joints = []
			self.doneLoading=1
			if self.self_collision:
				self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
					self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
					basePosition=self.basePosition,
					baseOrientation=self.baseOrientation,
					useFixedBase=self.fixed_base,
					flags=pybullet.URDF_USE_SELF_COLLISION))
			else:
				self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
					self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
					basePosition=self.basePosition,
					baseOrientation=self.baseOrientation,
					useFixedBase=self.fixed_base))

HumanoidBulletEnv-v0 crashing in multiple RL frameworks

Hello. I have been trying to train an agent in HumanoidBulletEnv-v0.
I have tried using multiple frameworks and algorithms, but have not been able to obtain a good policy in this particular environment. I faced similar issues using the RoboschoolHumanoid-v1 environment.
I choose to open this issue because most frameworks crashed at some point during the training of these two Humanoid environments.
Other simpler environments (such as Hopper and Walker) could be learned with no issues.

Most crashes seem to be caused by: reward == minus infinity, KL divergence == NaN or similar numerical errors.
Below is a brief summary of my experiments using both HumanoidBulletEnv-v0 and RoboschoolHumanoid-v1:

env framework algo result
RoboschoolHumanoid-v1 anyrl-py PPO Error: act==nan
RoboschoolHumanoid-v1 TensorForce PPO low reward stall
RoboschoolHumanoid-v1 Coach PPO Error: kl==nan
RoboschoolHumanoid-v1 Coach A3C low reward stall
RoboschoolHumanoid-v1 Baselines PPO Error: rew==-inf and kl=nan
HumanoidBulletEnv-v0 TensorForce PPO low reward stall
HumanoidBulletEnv-v0 Coach PPO Error: kl==nan
HumanoidBulletEnv-v0 Coach DDPG Error: assert(np.isfinite(a).all())
HumanoidBulletEnv-v0 TensorFlow Agents PPO Error: invalid fastbin entry

If you have interest, I can also paste here each individual Traceback.
Also, I'm not sure if this issue should be opened in the Bullet repo.

How to modify Mujoco environments?

I am working on the environment InvertedPendulumMuJoCoEnv-v0 and would like to change some parameters, such as the size/mass of the pole. I traced the code, and it seems the relevant parameters are in pybulletgym/envs/assets/mjcf/inverted_pendulum.xml. However, after editing the xml, it doesn't seem like anything changes in simulation. What am I missing? Is there some procedure to make the modifications take effect?

Thank you so much for your work, I really appreciate it!

Why are all the free joints in the asset xml files commented out?

I notice in all the asset xml files, the free joints are commented out.

For example, in the ant.xml line 14 is commented out.
""

What is the reason for this?

Is there any way to reproduce the same effect as using free joint i.e free joint has 6DOF (3 translational and 3 rotational degrees of freedom).

To be more specific, I want to rotate the object but cannot find a way to do so without using free joints.

Recommended way to change the robot mass

Hi, thanks a lot for the effort towards getting free from expensive licenses!

I was wondering if there is a recommended way to change properties like the robot mass?

Thank you in advance for your attention.

Cheers
Luca

env not rendering

import gym
import pybulletgym
import time
env = gym.make('HumanoidPyBulletEnv-v0')
for i_episode in range(500):
observation = env.reset()
for t in range(1000):
env.render()
action = env.action_space.sample()
observation, reward, done, info = env.step(action)
print(observation)
time.sleep(1/30)
if done:
print("Episode finished after {} timesteps".format(t+1))
break

Add fedora install notes

Please add these to help other fedora users

dnf install openmpi-devel python3-devel 
which mpiexec
# if not found: 
# export PATH=$PATH:/usr/lib64/openmpi/bin/
# echo 'export PATH=$PATH:/usr/lib64/openmpi/bin/' >> /etc/profile

pip3 install mpi4py 

pip3 install pybullet

ModuleNotFoundError when importing pybulletgym

I followed the readme instructions and successfully installed pybullet and pybulletgym on my VMware Ubuntu 18.04 VM but when I do import pybulletgym I get a ModuleNotFoundError. Anyone know what the issue could be?

get pixel as observation

Hello

I would like to have some sort of camera(fixed with respect to the agent) and get pixel observations instead of low dimensional outputs.
I would appreciate if anybody has any ideas.
Thanks

v2 environments from openai gym

I need some other environments from the openai gym. Any guidelines to help to port the rest of the environments from there?

Make it compatible with the MuJoCo environments

First off, it needs to be compatible with agents trained on MuJoCo trained envs. Any contribution welcome of such agents! Just post here if you have a set of well trained MuJoCo task agents.

If somebody even has a trace of observations together with the agent, that could be super helpful to find the differences.

Failed to create an OpenGL context

Hello,
I tried to launch an example but it fails at env.reset() with the following:

$ python enjoy_TF_AntBulletEnv_v0_2017may.py 
pybullet build time: May 11 2018 16:36:39
WARN: gym.spaces.Box autodetected dtype as <class 'numpy.float32'>. Please provide explicit dtype.
WARN: gym.spaces.Box autodetected dtype as <class 'numpy.float32'>. Please provide explicit dtype.
WARN: gym.spaces.Box autodetected dtype as <class 'numpy.float32'>. Please provide explicit dtype.
WARN: gym.spaces.Box autodetected dtype as <class 'numpy.float32'>. Please provide explicit dtype.
WalkerBase::__init__
WARN: Environment '<class 'pybulletgym.envs.gym_locomotion_envs.AntBulletEnv'>' has deprecated methods '_step' and '_reset' rather than 'step' and 'reset'. Compatibility code invoked. Set _gym_disable_underscore_compat = True to disable this behavior.
startThreads creating 1 threads.
starting thread 0
started thread 0 
argc=2
argv[0] = --unused
argv[1] = --start_demo_name=Physics Server
ExampleBrowserThreadFunc started
X11 functions dynamically loaded using dlopen/dlsym OK!
Creating context
Failed to create GL 3.0 context ... using old-style GLX context
Failed to create an OpenGL context

I don't know what would cause this. I was able to successfully launch the roboschool examples.

I use Arch Linux and the following packages: python-pybullet-git, python-gym-git, roboschool-git

Trainer modules

I am trying to run the "train_KerasDDPG_ReacherBulletEnv.py" example but it seems that the modules are not being imported properly for me among other issues.

For example, "from ..Trainer import Trainer" seems to be missing and to be one directory higher. When I do fix this issue, i'm running into other problems such as the method "Trainer.Trainer()" not existing.

I was wondering if I was missing something obvious or if these examples are not up to date anymore?

Thanks!

Are pretrained models MuJoCo compatible?

Hi,

I already had to model my environments in MuJoCo due to baseline algorithms that used it. As a proof of concept, I would like to use you pretrained Humanoid and let it run through my environment. I tried to model the observations based on your code, but didn't succeed so far. I can send my code if you want.

Do you think it such port is even possible? It seems that the actions are too large.

Thank you,
Lukas

Floor pattern not present

Hi,
for the environments like HalfCheetah, Ant etc, there is no floor pattern, is this desired? Cause in MuJoCo there is a tiled floor that can help for vision based tasks.

Memory leak error

Hello!
I had found same bug cause by newest numpy version 1.16.0,
which makes the environments get memory leak.
when I install pybullet-gym with numpy 1.16.0,
the memory use rate become higher and higher...
then I downgrade numpy to 1.15.4, the problem is solved.

How to Cite PyBullet-Gym

Would you kindly provide a preferred means of citing this library as a bibtex?

Something similar to how PyBullet does it would be appreciated:
@misc{coumans2019,
author = {Erwin Coumans and Yunfei Bai},
title = {PyBullet, a Python module for physics simulation for games, robotics and machine learning},
howpublished = {\url{http://pybullet.org}},
year = {2016--2019}
}

Contributions

I am interested in contributing to this project. Do you want to lay out a more detailed roadmap for others who might be interested in making contributions?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.