Change import gymnasium to import gymnasium as gym (#20)

This commit is contained in:
Mark Towers
2022-09-16 23:41:27 +01:00
committed by GitHub
parent 54872abbeb
commit 8589523a77
110 changed files with 657 additions and 633 deletions

View File

@@ -51,7 +51,7 @@ class Env(Generic[ObsType, ActType]):
- :attr:`action_space` - The Space object corresponding to valid actions
- :attr:`observation_space` - The Space object corresponding to valid observations
- :attr:`reward_range` - A tuple corresponding to the minimum and maximum possible rewards
- :attr:`spec` - An environment spec that contains the information used to initialise the environment from `gymnasium.make`
- :attr:`spec` - An environment spec that contains the information used to initialise the environment from `gym.make`
- :attr:`metadata` - The metadata of the environment, i.e. render modes
- :attr:`np_random` - The random number generator for the environment
@@ -187,7 +187,7 @@ class Env(Generic[ObsType, ActType]):
"""Returns the base non-wrapped environment.
Returns:
Env: The base non-wrapped gymnasium.Env instance
Env: The base non-wrapped gym.Env instance
"""
return self
@@ -361,7 +361,7 @@ class ObservationWrapper(Wrapper):
``observation["target_position"] - observation["agent_position"]``. For this, you could implement an
observation wrapper like this::
class RelativePosition(gymnasium.ObservationWrapper):
class RelativePosition(gym.ObservationWrapper):
def __init__(self, env):
super().__init__(env)
self.observation_space = Box(shape=(2,), low=-np.inf, high=np.inf)
@@ -435,7 +435,7 @@ class ActionWrapper(Wrapper):
Lets say you have an environment with action space of type :class:`gymnasium.spaces.Box`, but you would only like
to use a finite subset of actions. Then, you might want to implement the following wrapper::
class DiscreteActions(gymnasium.ActionWrapper):
class DiscreteActions(gym.ActionWrapper):
def __init__(self, env, disc_to_cont):
super().__init__(env)
self.disc_to_cont = disc_to_cont
@@ -445,7 +445,7 @@ class ActionWrapper(Wrapper):
return self.disc_to_cont[act]
if __name__ == "__main__":
env = gymnasium.make("LunarLanderContinuous-v2")
env = gym.make("LunarLanderContinuous-v2")
wrapped_env = DiscreteActions(env, [np.array([1,0]), np.array([-1,0]),
np.array([0,1]), np.array([0,-1])])
print(wrapped_env.action_space) #Discrete(4)

View File

@@ -5,7 +5,7 @@ from typing import TYPE_CHECKING, List, Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import error, spaces
from gymnasium.error import DependencyNotInstalled
from gymnasium.utils import EzPickle
@@ -100,7 +100,7 @@ class ContactDetector(contactListener):
leg.ground_contact = False
class BipedalWalker(gymnasium.Env, EzPickle):
class BipedalWalker(gym.Env, EzPickle):
"""
### Description
This is a simple 4-joint walker robot environment.
@@ -144,12 +144,12 @@ class BipedalWalker(gymnasium.Env, EzPickle):
To use to the _hardcore_ environment, you need to specify the
`hardcore=True` argument like below:
```python
import gymnasium
env = gymnasium.make("BipedalWalker-v3", hardcore=True)
import gymnasium as gym
env = gym.make("BipedalWalker-v3", hardcore=True)
```
### Version History
- v3: returns closest lidar trace instead of furthest;
- v3: Returns the closest lidar trace instead of furthest;
faster video recording
- v2: Count energy spent
- v1: Legs now report contact with ground; motors have higher torque and
@@ -762,8 +762,8 @@ class BipedalWalkerHardcore:
raise error.Error(
"Error initializing BipedalWalkerHardcore Environment.\n"
"Currently, we do not support initializing this mode of environment by calling the class directly.\n"
"To use this environment, instead create it by specifying the hardcore keyword in gymnasium.make, i.e.\n"
'gymnasium.make("BipedalWalker-v3", hardcore=True)'
"To use this environment, instead create it by specifying the hardcore keyword in gym.make, i.e.\n"
'gym.make("BipedalWalker-v3", hardcore=True)'
)

View File

@@ -5,7 +5,7 @@ from typing import Optional, Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.envs.box2d.car_dynamics import Car
from gymnasium.error import DependencyNotInstalled, InvalidAction
@@ -104,7 +104,7 @@ class FrictionDetector(contactListener):
obj.tiles.remove(tile)
class CarRacing(gymnasium.Env, EzPickle):
class CarRacing(gym.Env, EzPickle):
"""
### Description
The easiest control task to learn from pixels - a top-down
@@ -127,7 +127,8 @@ class CarRacing(gymnasium.Env, EzPickle):
There are 5 actions: do nothing, steer left, steer right, gas, brake.
### Observation Space
State consists of 96x96 pixels.
A top-down 96x96 RGB image of the car and race track.
### Rewards
The reward is -0.1 every frame and +1000/N for every track tile visited,
@@ -139,8 +140,8 @@ class CarRacing(gymnasium.Env, EzPickle):
The car starts at rest in the center of the road.
### Episode Termination
The episode finishes when all of the tiles are visited. The car can also go
outside of the playfield - that is, far off the track, in which case it will
The episode finishes when all the tiles are visited. The car can also go
outside the playfield - that is, far off the track, in which case it will
receive -100 reward and die.
### Arguments
@@ -158,17 +159,18 @@ class CarRacing(gymnasium.Env, EzPickle):
Correspondingly, passing the option `options["randomize"] = False` will not change the current colour of the environment.
`domain_randomize` must be `True` on init for this argument to work.
Example usage:
```py
env = gymnasium.make("CarRacing-v1", domain_randomize=True)
```python
import gymnasium as gym
env = gym.make("CarRacing-v1", domain_randomize=True)
# normal reset, this changes the colour scheme by default
env.reset()
# normal reset, this changes the colour scheme by default
env.reset()
# reset with colour scheme change
env.reset(options={"randomize": True})
# reset with colour scheme change
env.reset(options={"randomize": True})
# reset with no colour scheme change
env.reset(options={"randomize": False})
# reset with no colour scheme change
env.reset(options={"randomize": False})
```
### Version History

View File

@@ -6,7 +6,7 @@ from typing import TYPE_CHECKING, Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import error, spaces
from gymnasium.error import DependencyNotInstalled
from gymnasium.utils import EzPickle, colorize
@@ -74,7 +74,7 @@ class ContactDetector(contactListener):
self.env.legs[i].ground_contact = False
class LunarLander(gymnasium.Env, EzPickle):
class LunarLander(gym.Env, EzPickle):
"""
### Description
This environment is a classic rocket trajectory optimization problem.
@@ -141,8 +141,8 @@ class LunarLander(gymnasium.Env, EzPickle):
To use to the _continuous_ environment, you need to specify the
`continuous=True` argument like below:
```python
import gymnasium
env = gymnasium.make(
import gymnasium as gym
env = gym.make(
"LunarLander-v2",
continuous: bool = False,
gravity: float = -10.0,
@@ -173,7 +173,7 @@ class LunarLander(gymnasium.Env, EzPickle):
`turbulence_power` dictates the maximum magnitude of rotational wind applied to the craft. The recommended value for `turbulence_power` is between 0.0 and 2.0.
### Version History
- v2: Count energy spent and in v0.24, added turbulance with wind power and turbulence_power parameters
- v2: Count energy spent and in v0.24, added turbulence with wind power and turbulence_power parameters
- v1: Legs contact with ground added in state vector; contact with ground
give +10 reward points, and -10 if then lose contact; reward
renormalized to 200; harder initial random push.
@@ -802,8 +802,8 @@ class LunarLanderContinuous:
raise error.Error(
"Error initializing LunarLanderContinuous Environment.\n"
"Currently, we do not support initializing this mode of environment by calling the class directly.\n"
"To use this environment, instead create it by specifying the continuous keyword in gymnasium.make, i.e.\n"
'gymnasium.make("LunarLander-v2", continuous=True)'
"To use this environment, instead create it by specifying the continuous keyword in gym.make, i.e.\n"
'gym.make("LunarLander-v2", continuous=True)'
)

View File

@@ -4,7 +4,7 @@ from typing import Optional
import numpy as np
from numpy import cos, pi, sin
from gymnasium import core, spaces
from gymnasium import Env, spaces
from gymnasium.error import DependencyNotInstalled
__copyright__ = "Copyright 2013, RLPy http://acl.mit.edu/RLPy"
@@ -23,7 +23,7 @@ __author__ = "Christoph Dann <cdann@cdann.de>"
from gymnasium.envs.classic_control import utils
class AcrobotEnv(core.Env):
class AcrobotEnv(Env):
"""
### Description
@@ -94,20 +94,24 @@ class AcrobotEnv(core.Env):
### Arguments
No additional arguments are currently supported.
No additional arguments are currently supported during construction.
```python
import gymnasium as gym
env = gym.make('Acrobot-v1')
```
env = gymnasium.make('Acrobot-v1')
```
On reset, the `options` parameter allows the user to change the bounds used to determine
the new random state.
By default, the dynamics of the acrobot follow those described in Sutton and Barto's book
[Reinforcement Learning: An Introduction](http://incompleteideas.net/book/11/node4.html).
However, a `book_or_nips` parameter can be modified to change the pendulum dynamics to those described
in the original [NeurIPS paper](https://papers.nips.cc/paper/1995/hash/8f1d43620bc6bb580df6e80b0dc05c48-Abstract.html).
```
```python
# To change the dynamics as described above
env.env.book_or_nips = 'nips'
env.unwrapped.book_or_nips = 'nips'
```
See the following note for details:

View File

@@ -8,13 +8,13 @@ from typing import Optional, Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import logger, spaces
from gymnasium.envs.classic_control import utils
from gymnasium.error import DependencyNotInstalled
class CartPoleEnv(gymnasium.Env[np.ndarray, Union[int, np.ndarray]]):
class CartPoleEnv(gym.Env[np.ndarray, Union[int, np.ndarray]]):
"""
### Description
@@ -74,11 +74,13 @@ class CartPoleEnv(gymnasium.Env[np.ndarray, Union[int, np.ndarray]]):
### Arguments
```
gymnasium.make('CartPole-v1')
```python
import gymnasium as gym
gym.make('CartPole-v1')
```
No additional arguments are currently supported.
On reset, the `options` parameter allows the user to change the bounds used to determine
the new random state.
"""
metadata = {

View File

@@ -18,13 +18,13 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.envs.classic_control import utils
from gymnasium.error import DependencyNotInstalled
class Continuous_MountainCarEnv(gymnasium.Env):
class Continuous_MountainCarEnv(gym.Env):
"""
### Description
@@ -91,9 +91,13 @@ class Continuous_MountainCarEnv(gymnasium.Env):
### Arguments
```python
import gymnasium as gym
gym.make('MountainCarContinuous-v0')
```
gymnasium.make('MountainCarContinuous-v0')
```
On reset, the `options` parameter allows the user to change the bounds used to determine
the new random state.
### Version History

View File

@@ -7,13 +7,13 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.envs.classic_control import utils
from gymnasium.error import DependencyNotInstalled
class MountainCarEnv(gymnasium.Env):
class MountainCarEnv(gym.Env):
"""
### Description
@@ -66,7 +66,6 @@ class MountainCarEnv(gymnasium.Env):
upon collision with the wall. The position is clipped to the range `[-1.2, 0.6]` and
velocity is clipped to the range `[-0.07, 0.07]`.
### Reward:
The goal is to reach the flag placed on top of the right hill as quickly as possible, as such the agent is
@@ -86,9 +85,13 @@ class MountainCarEnv(gymnasium.Env):
### Arguments
```python
import gymnasium as gym
gym.make('MountainCar-v0')
```
gymnasium.make('MountainCar-v0')
```
On reset, the `options` parameter allows the user to change the bounds used to determine
the new random state.
### Version History

View File

@@ -5,7 +5,7 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.envs.classic_control import utils
from gymnasium.error import DependencyNotInstalled
@@ -14,7 +14,7 @@ DEFAULT_X = np.pi
DEFAULT_Y = 1.0
class PendulumEnv(gymnasium.Env):
class PendulumEnv(gym.Env):
"""
### Description
@@ -76,9 +76,13 @@ class PendulumEnv(gymnasium.Env):
- `g`: acceleration of gravity measured in *(m s<sup>-2</sup>)* used to calculate the pendulum dynamics.
The default value is g = 10.0 .
```python
import gymnasium as gym
gym.make('Pendulum-v1', g=9.81)
```
gymnasium.make('Pendulum-v1', g=9.81)
```
On reset, the `options` parameter allows the user to change the bounds used to determine
the new random state.
### Version History

View File

@@ -142,14 +142,16 @@ class AntEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
env = gymnasium.make('Ant-v2')
```python
import gymnasium as gym
env = gym.make('Ant-v2')
```
v3 and v4 take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and v4 take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('Ant-v4', ctrl_cost_weight=0.1, ...)
```python
import gymnasium as gym
env = gym.make('Ant-v4', ctrl_cost_weight=0.1, ...)
```
| Parameter | Type | Default |Description |
@@ -166,7 +168,7 @@ class AntEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -105,14 +105,16 @@ class HalfCheetahEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
env = gymnasium.make('HalfCheetah-v2')
```python
import gymnasium as gym
env = gym.make('HalfCheetah-v2')
```
v3 and v4 take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and v4 take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('HalfCheetah-v4', ctrl_cost_weight=0.1, ....)
```python
import gymnasium as gym
env = gym.make('HalfCheetah-v4', ctrl_cost_weight=0.1, ....)
```
| Parameter | Type | Default | Description |
@@ -126,7 +128,7 @@ class HalfCheetahEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -106,14 +106,16 @@ class HopperEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
env = gymnasium.make('Hopper-v2')
```python
import gymnasium as gym
env = gym.make('Hopper-v2')
```
v3 and v4 take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and v4 take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('Hopper-v4', ctrl_cost_weight=0.1, ....)
```python
import gymnasium as gym
env = gym.make('Hopper-v4', ctrl_cost_weight=0.1, ....)
```
| Parameter | Type | Default | Description |
@@ -132,7 +134,7 @@ class HopperEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -181,14 +181,16 @@ class HumanoidEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
env = gymnasium.make('Humanoid-v4')
```python
import gymnasium as gym
env = gym.make('Humanoid-v4')
```
v3 and v4 take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and v4 take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('Humanoid-v4', ctrl_cost_weight=0.1, ....)
```python
import gymnasium as gym
env = gym.make('Humanoid-v4', ctrl_cost_weight=0.1, ....)
```
| Parameter | Type | Default | Description |
@@ -206,7 +208,7 @@ class HumanoidEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -98,7 +98,7 @@ class HumanoidStandupEnv(MujocoEnv, utils.EzPickle):
| 42 | angular velocity of the angle between right upper arm and right_lower_arm | -Inf | Inf | right_elbow | hinge | anglular velocity (rad/s) |
| 43 | coordinate-1 (multi-axis) of the angular velocity of the angle between torso and left arm (in left_upper_arm) | -Inf | Inf | left_shoulder1 | hinge | anglular velocity (rad/s) |
| 44 | coordinate-2 (multi-axis) of the angular velocity of the angle between torso and left arm (in left_upper_arm) | -Inf | Inf | left_shoulder2 | hinge | anglular velocity (rad/s) |
| 45 | angular velocitty of the angle between left upper arm and left_lower_arm | -Inf | Inf | left_elbow | hinge | anglular velocity (rad/s) |
| 45 | angular velocity of the angle between left upper arm and left_lower_arm | -Inf | Inf | left_elbow | hinge | anglular velocity (rad/s) |
Additionally, after all the positional and velocity based values in the table,
@@ -161,18 +161,23 @@ class HumanoidStandupEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported.
```
env = gymnasium.make('HumanoidStandup-v4')
```python
import gymnasium as gym
env = gym.make('HumanoidStandup-v4')
```
There is no v3 for HumanoidStandup, unlike the robot environments where a v3 and
beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
```python
import gymnasium as gym
env = gym.make('HumanoidStandup-v2')
```
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -53,7 +53,7 @@ class InvertedDoublePendulumEnv(MujocoEnv, utils.EzPickle):
There is physical contact between the robots and their environment - and Mujoco
attempts at getting realisitic physics simulations for the possible physical contact
attempts at getting realistic physics simulations for the possible physical contact
dynamics by aiming for physical accuracy and computational efficiency.
There is one constraint force for contacts for each degree of freedom (3).
@@ -96,17 +96,22 @@ class InvertedDoublePendulumEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported.
```
env = gymnasium.make('InvertedDoublePendulum-v4')
```python
import gymnasium as gym
env = gym.make('InvertedDoublePendulum-v4')
```
There is no v3 for InvertedPendulum, unlike the robot environments where a v3 and
beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
beyond take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```python
import gymnasium as gym
env = gym.make('InvertedDoublePendulum-v2')
```
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks (including inverted pendulum)
* v0: Initial versions release (1.0.0)

View File

@@ -61,23 +61,27 @@ class InvertedPendulumEnv(MujocoEnv, utils.EzPickle):
1. Truncation: The episode duration reaches 1000 timesteps.
2. Termination: Any of the state space values is no longer finite.
3. Termination: The absolutely value of the vertical angle between the pole and the cart is greater than 0.2 radian.
3. Termination: The absolute value of the vertical angle between the pole and the cart is greater than 0.2 radian.
### Arguments
No additional arguments are currently supported.
```
env = gymnasium.make('InvertedPendulum-v4')
```python
import gymnasium as gym
env = gym.make('InvertedPendulum-v4')
```
There is no v3 for InvertedPendulum, unlike the robot environments where a
v3 and beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and beyond take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```python
import gymnasium as gym
env = gym.make('InvertedPendulum-v2')
```
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks (including inverted pendulum)
* v0: Initial versions release (1.0.0)

View File

@@ -112,13 +112,18 @@ class PusherEnv(MujocoEnv, utils.EzPickle):
but modifications can be made to the XML file in the assets folder
(or by changing the path to a modified XML file in another folder)..
```
env = gymnasium.make('Pusher-v4')
```python
import gymnasium as gym
env = gym.make('Pusher-v4')
```
There is no v3 for Pusher, unlike the robot environments where a v3 and
beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
beyond take `gymnasmium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```python
import gymnasium as gym
env = gym.make('Pusher-v2')
```
### Version History

View File

@@ -102,13 +102,13 @@ class ReacherEnv(MujocoEnv, utils.EzPickle):
but modifications can be made to the XML file in the assets folder
(or by changing the path to a modified XML file in another folder)..
```
env = gymnasium.make('Reacher-v4')
```python
import gymnasium as gym
env = gym.make('Reacher-v4')
```
There is no v3 for Reacher, unlike the robot environments where a v3 and
beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
beyond take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
### Version History

View File

@@ -96,14 +96,16 @@ class SwimmerEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
gymnasium.make('Swimmer-v4')
```python
import gymnasium as gym
gym.make('Swimmer-v4')
```
v3 and v4 take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and v4 take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('Swimmer-v4', ctrl_cost_weight=0.1, ....)
```python
import gymnasium as gym
env = gym.make('Swimmer-v4', ctrl_cost_weight=0.1, ....)
```
| Parameter | Type | Default | Description |
@@ -118,7 +120,7 @@ class SwimmerEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -111,14 +111,16 @@ class Walker2dEnv(MujocoEnv, utils.EzPickle):
No additional arguments are currently supported in v2 and lower.
```
env = gymnasium.make('Walker2d-v4')
```python
import gymnasium as gym
env = gym.make('Walker2d-v4')
```
v3 and beyond take gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc.
v3 and beyond take `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc.
```
env = gymnasium.make('Walker2d-v4', ctrl_cost_weight=0.1, ....)
```python
import gymnasium as gym
env = gym.make('Walker2d-v4', ctrl_cost_weight=0.1, ....)
```
| Parameter | Type | Default | Description |
@@ -137,7 +139,7 @@ class Walker2dEnv(MujocoEnv, utils.EzPickle):
### Version History
* v4: all mujoco environments now use the mujoco bindings in mujoco>=2.1.3
* v3: support for gymnasium.make kwargs such as xml_file, ctrl_cost_weight, reset_noise_scale etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v3: support for `gymnasium.make` kwargs such as `xml_file`, `ctrl_cost_weight`, `reset_noise_scale`, etc. rgb rendering comes from tracking camera (so agent does not run away from screen)
* v2: All continuous control environments now use mujoco_py >= 1.50
* v1: max_time_steps raised to 1000 for robot based tasks. Added reward_threshold to environments.
* v0: Initial versions release (1.0.0)

View File

@@ -116,17 +116,17 @@ def get_env_id(ns: Optional[str], name: str, version: Optional[int]) -> str:
@dataclass
class EnvSpec:
"""A specification for creating environments with `gymnasium.make`.
"""A specification for creating environments with `gym.make`.
* id: The string used to create the environment with `gymnasium.make`
* id: The string used to create the environment with `gym.make`
* entry_point: The location of the environment to create from
* reward_threshold: The reward threshold for completing the environment.
* nondeterministic: If the observation of an environment cannot be repeated with the same initial state, random number generator state and actions.
* max_episode_steps: The max number of steps that the environment can take before truncation
* order_enforce: If to enforce the order of `reset` before `step` and `render` functions
* autoreset: If to automatically reset the environment on episode end
* disable_env_checker: If to disable the environment checker wrapper in `gymnasium.make`, by default False (runs the environment checker)
* kwargs: Additional keyword arguments passed to the environments through `gymnasium.make`
* disable_env_checker: If to disable the environment checker wrapper in `gym.make`, by default False (runs the environment checker)
* kwargs: Additional keyword arguments passed to the environments through `gym.make`
"""
id: str
@@ -414,7 +414,7 @@ def _check_spec_register(spec: EnvSpec):
f"`{spec.id}` when the versioned environment "
f"`{latest_versioned_spec.id}` of the same name "
f"already exists. Note: the default behavior is "
f"that `gymnasium.make` with the unversioned environment "
f"that `gym.make` with the unversioned environment "
f"will return the latest versioned environment"
)

View File

@@ -3,7 +3,7 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.error import DependencyNotInstalled
@@ -46,7 +46,7 @@ def is_natural(hand): # Is this hand a natural blackjack?
return sorted(hand) == [1, 10]
class BlackjackEnv(gymnasium.Env):
class BlackjackEnv(gym.Env):
"""
Blackjack is a card game where the goal is to beat the dealer by obtaining cards
that sum to closer to 21 (without going over 21) than the dealers cards.
@@ -93,8 +93,9 @@ class BlackjackEnv(gymnasium.Env):
### Arguments
```
gymnasium.make('Blackjack-v1', natural=False, sab=False)
```python
import gymnasium as gym
gym.make('Blackjack-v1', natural=False, sab=False)
```
<a id="nat">`natural=False`</a>: Whether to give an additional reward for

View File

@@ -54,8 +54,9 @@ class CliffWalkingEnv(Env):
### Arguments
```
gymnasium.make('CliffWalking-v0')
```python
import gymnasium as gym
gym.make('CliffWalking-v0')
```
### Version History

View File

@@ -104,8 +104,9 @@ class FrozenLakeEnv(Env):
### Arguments
```
gymnasium.make('FrozenLake-v1', desc=None, map_name="4x4", is_slippery=True)
```python
import gymnasium as gym
gym.make('FrozenLake-v1', desc=None, map_name="4x4", is_slippery=True)
```
`desc`: Used to specify custom map for frozen lake. For example,
@@ -117,7 +118,7 @@ class FrozenLakeEnv(Env):
```
from gymnasium.envs.toy_text.frozen_lake import generate_random_map
gymnasium.make('FrozenLake-v1', desc=generate_random_map(size=8))
gym.make('FrozenLake-v1', desc=generate_random_map(size=8))
```
`map_name`: ID to use any of the preloaded maps.

View File

@@ -109,8 +109,9 @@ class TaxiEnv(Env):
### Arguments
```
gymnasium.make('Taxi-v3')
```python
import gymnasium as gym
gym.make('Taxi-v3')
```
### Version History

View File

@@ -3,7 +3,7 @@ from typing import Dict, List, Optional, Sequence, SupportsFloat, Tuple, Type, U
import numpy as np
import gymnasium.error
import gymnasium as gym
from gymnasium import logger
from gymnasium.spaces.space import Space
@@ -186,7 +186,7 @@ class Box(Space[np.ndarray]):
A sampled value from the Box
"""
if mask is not None:
raise gymnasium.error.Error(
raise gym.error.Error(
f"Box.sample cannot be provided a mask, actual value: {mask}"
)

View File

@@ -28,7 +28,8 @@ class Graph(Space):
Example usage::
self.observation_space = spaces.Graph(node_space=space.Box(low=-100, high=100, shape=(3,)), edge_space=spaces.Discrete(3))
>>> from gymnasium.spaces import Box, Discrete
>>> Graph(node_space=Box(low=-100, high=100, shape=(3,)), edge_space=Discrete(3))
"""
def __init__(

View File

@@ -29,8 +29,8 @@ class MultiDiscrete(Space[np.ndarray]):
Example::
>> d = MultiDiscrete(np.array([[1, 2], [3, 4]]))
>> d.sample()
>>> d = MultiDiscrete(np.array([[1, 2], [3, 4]]))
>>> d.sample()
array([[0, 0],
[2, 3]])
"""

View File

@@ -4,7 +4,7 @@ from typing import Any, List, Optional, Tuple, Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces.space import Space
@@ -34,7 +34,7 @@ class Sequence(Space[Tuple]):
seed: Optionally, you can use this argument to seed the RNG that is used to sample from the space.
"""
assert isinstance(
space, gymnasium.Space
space, gym.Space
), f"Expects the feature space to be instance of a gymnasium Space, actual type: {type(space)}"
self.feature_space = space
super().__init__(

View File

@@ -14,6 +14,7 @@ class Text(Space[str]):
r"""A space representing a string comprised of characters from a given charset.
Example::
>>> # {"", "B5", "hello", ...}
>>> Text(5)
>>> # {"0", "42", "0123456789", ...}

View File

@@ -19,7 +19,7 @@ from copy import deepcopy
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import logger, spaces
from gymnasium.utils.passive_env_checker import (
check_action_space,
@@ -59,7 +59,7 @@ def data_equivalence(data_1, data_2) -> bool:
return False
def check_reset_seed(env: gymnasium.Env):
def check_reset_seed(env: gym.Env):
"""Check that the environment can be reset with a seed.
Args:
@@ -123,12 +123,12 @@ def check_reset_seed(env: gymnasium.Env):
f"Actual default: {seed_param.default}"
)
else:
raise gymnasium.error.Error(
raise gym.error.Error(
"The `reset` method does not provide a `seed` or `**kwargs` keyword argument."
)
def check_reset_options(env: gymnasium.Env):
def check_reset_options(env: gym.Env):
"""Check that the environment can be reset with options.
Args:
@@ -151,12 +151,12 @@ def check_reset_options(env: gymnasium.Env):
f"This should never happen, please report this issue. The error was: {e}"
)
else:
raise gymnasium.error.Error(
raise gym.error.Error(
"The `reset` method does not provide an `options` or `**kwargs` keyword argument."
)
def check_reset_return_info_deprecation(env: gymnasium.Env):
def check_reset_return_info_deprecation(env: gym.Env):
"""Makes sure support for deprecated `return_info` argument is dropped.
Args:
@@ -173,7 +173,7 @@ def check_reset_return_info_deprecation(env: gymnasium.Env):
)
def check_seed_deprecation(env: gymnasium.Env):
def check_seed_deprecation(env: gym.Env):
"""Makes sure support for deprecated function `seed` is dropped.
Args:
@@ -189,7 +189,7 @@ def check_seed_deprecation(env: gymnasium.Env):
)
def check_reset_return_type(env: gymnasium.Env):
def check_reset_return_type(env: gym.Env):
"""Checks that :meth:`reset` correctly returns a tuple of the form `(obs , info)`.
Args:
@@ -252,7 +252,7 @@ def check_space_limit(space, space_type: str):
check_space_limit(subspace, space_type)
def check_env(env: gymnasium.Env, warn: bool = None, skip_render_check: bool = False):
def check_env(env: gym.Env, warn: bool = None, skip_render_check: bool = False):
"""Check that an environment follows Gym API.
This is an invasive function that calls the environment's reset and step.
@@ -270,7 +270,7 @@ def check_env(env: gymnasium.Env, warn: bool = None, skip_render_check: bool = F
logger.warn("`check_env(warn=...)` parameter is now ignored.")
assert isinstance(
env, gymnasium.Env
env, gym.Env
), "The environment must inherit from the gymnasium.Env class. See https://gymnasium.farama.org/content/environment_creation/ for more info."
if env.unwrapped is not env:

View File

@@ -4,7 +4,7 @@ from typing import Callable, Dict, List, Optional, Tuple, Union
import numpy as np
import gymnasium.error
import gymnasium as gym
from gymnasium import Env, logger
from gymnasium.core import ActType, ObsType
from gymnasium.error import DependencyNotInstalled
@@ -16,7 +16,7 @@ try:
from pygame.event import Event
from pygame.locals import VIDEORESIZE
except ImportError:
raise gymnasium.error.DependencyNotInstalled(
raise gym.error.DependencyNotInstalled(
"Pygame is not installed, run `pip install gymnasium[classic_control]`"
)
@@ -148,9 +148,9 @@ def play(
Example::
>>> import gymnasium
>>> import gymnasium as gym
>>> from gymnasium.utils.play import play
>>> play(gymnasium.make("CarRacing-v1", render_mode="rgb_array"), keys_to_action={
>>> play(gym.make("CarRacing-v1", render_mode="rgb_array"), keys_to_action={
... "w": np.array([0, 0.7, 0]),
... "a": np.array([-1, 0, 0]),
... "s": np.array([0, 0, 1]),
@@ -170,10 +170,11 @@ def play(
:class:`gym.utils.play.PlayPlot`. Here's a sample code for plotting the reward
for last 150 steps.
>>> import gymnasium as gym
>>> def callback(obs_t, obs_tp1, action, rew, terminated, truncated, info):
... return [rew,]
>>> plotter = PlayPlot(callback, 150, ["reward"])
>>> play(gymnasium.make("ALE/AirRaid-v5"), callback=plotter.callback)
>>> play(gym.make("CartPole-v1"), callback=plotter.callback)
Args:

View File

@@ -2,13 +2,13 @@
import os
from typing import Callable, Optional
import gymnasium
import gymnasium as gym
from gymnasium import logger
try:
from moviepy.video.io.ImageSequenceClip import ImageSequenceClip
except ImportError:
raise gymnasium.error.DependencyNotInstalled(
raise gym.error.DependencyNotInstalled(
"MoviePy is not installed, run `pip install moviepy`"
)
@@ -59,16 +59,17 @@ def save_video(
You need to specify either fps or duration.
Example:
>>> import gymnasium
>>> import gymnasium as gym
>>> from gymnasium.utils.save_video import save_video
>>> env = gymnasium.make("FrozenLake-v1", render_mode="rgb_array_list")
>>> env = gym.make("FrozenLake-v1", render_mode="rgb_array_list")
>>> env.reset()
>>> step_starting_index = 0
>>> episode_index = 0
>>> for step_index in range(199):
... action = env.action_space.sample()
... _, _, done, _ = env.step(action)
... if done:
... _, _, terminated, truncated, _ = env.step(action)
...
... if terminated or truncated:
... save_video(
... env.render(),
... "videos",

View File

@@ -145,14 +145,18 @@ def step_api_compatibility(
is_vector_env (bool): Whether the step_returns are from a vector environment
Returns:
step_returns (tuple): Depending on `output_truncation_bool` bool, it can return (obs, rew, done, info) or (obs, rew, terminated, truncated, info)
step_returns (tuple): Depending on `output_truncation_bool` bool, it can return `(obs, rew, done, info)` or `(obs, rew, terminated, truncated, info)`
Examples:
This function can be used to ensure compatibility in step interfaces with conflicting API. Eg. if env is written in old API,
wrapper is written in new API, and the final step output is desired to be in old API.
>>> import gymnasium as gym
>>> env = gym.make("OldEnv")
>>> obs, rew, done, info = step_api_compatibility(env.step(action), output_truncation_bool=False)
>>> obs, rew, terminated, truncated, info = step_api_compatibility(env.step(action), output_truncation_bool=True)
>>> vec_env = gym.vector.make("OldEnv")
>>> observations, rewards, dones, infos = step_api_compatibility(vec_env.step(action), is_vector_env=True)
"""
if output_truncation_bool:

View File

@@ -1,7 +1,7 @@
"""Module for vector environments."""
from typing import Iterable, List, Optional, Union
import gymnasium
import gymnasium as gym
from gymnasium.vector.async_vector_env import AsyncVectorEnv
from gymnasium.vector.sync_vector_env import SyncVectorEnv
from gymnasium.vector.vector_env import VectorEnv, VectorEnvWrapper
@@ -21,8 +21,8 @@ def make(
Example::
>>> import gymnasium
>>> env = gymnasium.vector.make('CartPole-v1', num_envs=3)
>>> import gymnasium as gym
>>> env = gym.vector.make('CartPole-v1', num_envs=3)
>>> env.reset()
array([[-0.04456399, 0.04653909, 0.01326909, -0.02099827],
[ 0.03073904, 0.00145001, -0.03088818, -0.03131252],
@@ -48,7 +48,7 @@ def make(
_disable_env_checker = True if env_num > 0 else disable_env_checker
def _make_env():
env = gymnasium.envs.registration.make(
env = gym.envs.registration.make(
id,
disable_env_checker=_disable_env_checker,
**kwargs,

View File

@@ -8,7 +8,7 @@ from typing import List, Optional, Sequence, Tuple, Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import logger
from gymnasium.core import ObsType
from gymnasium.error import (
@@ -46,10 +46,10 @@ class AsyncVectorEnv(VectorEnv):
Example::
>>> import gymnasium
>>> env = gymnasium.vector.AsyncVectorEnv([
... lambda: gymnasium.make("Pendulum-v0", g=9.81),
... lambda: gymnasium.make("Pendulum-v0", g=1.62)
>>> import gymnasium as gym
>>> env = gym.vector.AsyncVectorEnv([
... lambda: gym.make("Pendulum-v0", g=9.81),
... lambda: gym.make("Pendulum-v0", g=1.62)
... ])
>>> env.reset()
array([[-0.8286432 , 0.5597771 , 0.90249056],
@@ -59,8 +59,8 @@ class AsyncVectorEnv(VectorEnv):
def __init__(
self,
env_fns: Sequence[callable],
observation_space: Optional[gymnasium.Space] = None,
action_space: Optional[gymnasium.Space] = None,
observation_space: Optional[gym.Space] = None,
action_space: Optional[gym.Space] = None,
shared_memory: bool = True,
copy: bool = True,
context: Optional[str] = None,

View File

@@ -17,10 +17,10 @@ class SyncVectorEnv(VectorEnv):
Example::
>>> import gymnasium
>>> env = gymnasium.vector.SyncVectorEnv([
... lambda: gymnasium.make("Pendulum-v0", g=9.81),
... lambda: gymnasium.make("Pendulum-v0", g=1.62)
>>> import gymnasium as gym
>>> env = gym.vector.SyncVectorEnv([
... lambda: gym.make("Pendulum-v0", g=9.81),
... lambda: gym.make("Pendulum-v0", g=1.62)
... ])
>>> env.reset()
array([[-0.8286432 , 0.5597771 , 0.90249056],

View File

@@ -3,13 +3,13 @@ from typing import Any, List, Optional, Tuple, Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.vector.utils.spaces import batch_space
__all__ = ["VectorEnv"]
class VectorEnv(gymnasium.Env):
class VectorEnv(gym.Env):
"""Base class for vectorized environments. Runs multiple independent copies of the same environment in parallel.
This is not the same as 1 environment that has multiple subcomponents, but it is many copies of the same base env.
@@ -25,8 +25,8 @@ class VectorEnv(gymnasium.Env):
def __init__(
self,
num_envs: int,
observation_space: gymnasium.Space,
action_space: gymnasium.Space,
observation_space: gym.Space,
action_space: gym.Space,
):
"""Base class for vectorized environments.

View File

@@ -3,23 +3,16 @@
Wrappers are used to transform an environment in a modular way:
```python
env = gym.make('Pong-v0')
import gymnasium as gym
env = gym.make('CartPole-v1')
env = MyWrapper(env)
```
Note that we may later restructure any of the files in this directory,
but will keep the wrappers available at the wrappers' top-level
folder. So for example, you should access `MyWrapper` as follows:
```python
from gymnasium.wrappers import MyWrapper
```
## Quick tips for writing your own wrapper
- Don't forget to call `super(class_name, self).__init__(env)` if you override the wrapper's `__init__` function
- You can access the inner environment with `self.unwrapped`
- You can access the previous layer using `self.env`
- You can access the previous wrapper using `self.env`
- The variables `metadata`, `action_space`, `observation_space`, `reward_range`, and `spec` are copied to `self` from the previous layer
- Create a wrapped function for at least one of the following: `__init__(self, env)`, `step`, `reset`, `render`, `close`, or `seed`
- Your layered function should take its input from the previous layer (`self.env`) and/or the inner layer (`self.unwrapped`)

View File

@@ -1,7 +1,7 @@
"""Implementation of Atari 2600 Preprocessing following the guidelines of Machado et al., 2018."""
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box
try:
@@ -10,7 +10,7 @@ except ImportError:
cv2 = None
class AtariPreprocessing(gymnasium.Wrapper):
class AtariPreprocessing(gym.Wrapper):
"""Atari 2600 preprocessing wrapper.
This class follows the guidelines in Machado et al. (2018),
@@ -29,7 +29,7 @@ class AtariPreprocessing(gymnasium.Wrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
noop_max: int = 30,
frame_skip: int = 4,
screen_size: int = 84,
@@ -60,7 +60,7 @@ class AtariPreprocessing(gymnasium.Wrapper):
"""
super().__init__(env)
if cv2 is None:
raise gymnasium.error.DependencyNotInstalled(
raise gym.error.DependencyNotInstalled(
"opencv-python package not installed, run `pip install gymnasium[other]` to get dependencies for atari"
)
assert frame_skip > 0

View File

@@ -1,8 +1,8 @@
"""Wrapper that autoreset environments when `terminated=True` or `truncated=True`."""
import gymnasium
import gymnasium as gym
class AutoResetWrapper(gymnasium.Wrapper):
class AutoResetWrapper(gym.Wrapper):
"""A class for providing an automatic reset functionality for gymnasium environments when calling :meth:`self.step`.
When calling step causes :meth:`Env.step` to return `terminated=True` or `truncated=True`, :meth:`Env.reset` is called,
@@ -24,7 +24,7 @@ class AutoResetWrapper(gymnasium.Wrapper):
Make sure you know what you're doing if you use this wrapper!
"""
def __init__(self, env: gymnasium.Env):
def __init__(self, env: gym.Env):
"""A class for providing an automatic reset functionality for gymnasium environments when calling :meth:`self.step`.
Args:

View File

@@ -1,7 +1,7 @@
"""Wrapper for clipping actions within a valid bound."""
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import ActionWrapper
from gymnasium.spaces import Box
@@ -10,8 +10,8 @@ class ClipAction(ActionWrapper):
"""Clip the continuous action within the valid :class:`Box` observation space bound.
Example:
>>> import gymnasium
>>> env = gymnasium.make('Bipedal-Walker-v3')
>>> import gymnasium as gym
>>> env = gym.make('Bipedal-Walker-v3')
>>> env = ClipAction(env)
>>> env.action_space
Box(-1.0, 1.0, (4,), float32)
@@ -19,7 +19,7 @@ class ClipAction(ActionWrapper):
# Executes the action np.array([1.0, 1.0, -1.0, 0]) in the base environment
"""
def __init__(self, env: gymnasium.Env):
def __init__(self, env: gym.Env):
"""A wrapper for clipping continuous actions within the valid bound.
Args:

View File

@@ -2,7 +2,7 @@
import sys
from typing import Any, Dict, Optional, Tuple
import gymnasium
import gymnasium as gym
from gymnasium.core import ObsType
from gymnasium.utils.step_api_compatibility import (
convert_to_terminated_truncated_step_api,
@@ -21,8 +21,8 @@ else:
class LegacyEnv(Protocol):
"""A protocol for environments using the old step API."""
observation_space: gymnasium.Space
action_space: gymnasium.Space
observation_space: gym.Space
action_space: gym.Space
def reset(self) -> Any:
"""Reset the environment and return the initial observation."""
@@ -45,7 +45,7 @@ class LegacyEnv(Protocol):
...
class EnvCompatibility(gymnasium.Env):
class EnvCompatibility(gym.Env):
r"""A wrapper which can transform an environment from the old API to the new API.
Old step API refers to step() method returning (observation, reward, done, info), and reset() only retuning the observation.

View File

@@ -1,5 +1,5 @@
"""A passive environment checker wrapper for an environment's observation and action space along with the reset, step and render functions."""
import gymnasium
import gymnasium as gym
from gymnasium.core import ActType
from gymnasium.utils.passive_env_checker import (
check_action_space,
@@ -10,7 +10,7 @@ from gymnasium.utils.passive_env_checker import (
)
class PassiveEnvChecker(gymnasium.Wrapper):
class PassiveEnvChecker(gym.Wrapper):
"""A passive environment checker wrapper that surrounds the step, reset and render functions to check they follow the gymnasium API."""
def __init__(self, env):

View File

@@ -2,19 +2,19 @@
import copy
from typing import Sequence
import gymnasium
import gymnasium as gym
from gymnasium import spaces
class FilterObservation(gymnasium.ObservationWrapper):
class FilterObservation(gym.ObservationWrapper):
"""Filter Dict observation space by the keys.
Example:
>>> import gymnasium
>>> env = gymnasium.wrappers.TransformObservation(
... gymnasium.make('CartPole-v1'), lambda obs: {'obs': obs, 'time': 0}
>>> import gymnasium as gym
>>> env = gym.wrappers.TransformObservation(
... gym.make('CartPole-v1'), lambda obs: {'obs': obs, 'time': 0}
... )
>>> env.observation_space = gymnasium.spaces.Dict(obs=env.observation_space, time=gymnasium.spaces.Discrete(1))
>>> env.observation_space = gym.spaces.Dict(obs=env.observation_space, time=gym.spaces.Discrete(1))
>>> env.reset()
{'obs': array([-0.00067088, -0.01860439, 0.04772898, -0.01911527], dtype=float32), 'time': 0}
>>> env = FilterObservation(env, filter_keys=['time'])
@@ -24,7 +24,7 @@ class FilterObservation(gymnasium.ObservationWrapper):
({'obs': array([ 0.04649447, -0.14996664, -0.03329664, 0.25847703], dtype=float32)}, 1.0, False, {})
"""
def __init__(self, env: gymnasium.Env, filter_keys: Sequence[str] = None):
def __init__(self, env: gym.Env, filter_keys: Sequence[str] = None):
"""A wrapper that filters dictionary observations by their keys.
Args:

View File

@@ -1,25 +1,25 @@
"""Wrapper for flattening observations of an environment."""
import gymnasium
import gymnasium.spaces as spaces
import gymnasium as gym
from gymnasium import spaces
class FlattenObservation(gymnasium.ObservationWrapper):
class FlattenObservation(gym.ObservationWrapper):
"""Observation wrapper that flattens the observation.
Example:
>>> import gymnasium
>>> env = gymnasium.make('CarRacing-v1')
>>> import gymnasium as gym
>>> env = gym.make('CarRacing-v1')
>>> env.observation_space.shape
(96, 96, 3)
>>> env = FlattenObservation(env)
>>> env.observation_space.shape
(27648,)
>>> obs = env.reset()
>>> obs, info = env.reset()
>>> obs.shape
(27648,)
"""
def __init__(self, env: gymnasium.Env):
def __init__(self, env: gym.Env):
"""Flattens the observations of an environment.
Args:

View File

@@ -4,7 +4,7 @@ from typing import Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.error import DependencyNotInstalled
from gymnasium.spaces import Box
@@ -97,7 +97,7 @@ class LazyFrames:
return frame
class FrameStack(gymnasium.ObservationWrapper):
class FrameStack(gym.ObservationWrapper):
"""Observation wrapper that stacks the observations in a rolling manner.
For example, if the number of stacks is 4, then the returned observation contains
@@ -112,8 +112,8 @@ class FrameStack(gymnasium.ObservationWrapper):
- After :meth:`reset` is called, the frame buffer will be filled with the initial observation. I.e. the observation returned by :meth:`reset` will consist of ``num_stack`-many identical frames,
Example:
>>> import gymnasium
>>> env = gymnasium.make('CarRacing-v1')
>>> import gymnasium as gym
>>> env = gym.make('CarRacing-v1')
>>> env = FrameStack(env, 4)
>>> env.observation_space
Box(4, 96, 96, 3)
@@ -124,7 +124,7 @@ class FrameStack(gymnasium.ObservationWrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
num_stack: int,
lz4_compress: bool = False,
):

View File

@@ -1,26 +1,26 @@
"""Wrapper that converts a color observation to grayscale."""
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box
class GrayScaleObservation(gymnasium.ObservationWrapper):
class GrayScaleObservation(gym.ObservationWrapper):
"""Convert the image observation from RGB to gray scale.
Example:
>>> env = gymnasium.make('CarRacing-v1')
>>> env = gym.make('CarRacing-v1')
>>> env.observation_space
Box(0, 255, (96, 96, 3), uint8)
>>> env = GrayScaleObservation(gymnasium.make('CarRacing-v1'))
>>> env = GrayScaleObservation(gym.make('CarRacing-v1'))
>>> env.observation_space
Box(0, 255, (96, 96), uint8)
>>> env = GrayScaleObservation(gymnasium.make('CarRacing-v1'), keep_dim=True)
>>> env = GrayScaleObservation(gym.make('CarRacing-v1'), keep_dim=True)
>>> env.observation_space
Box(0, 255, (96, 96, 1), uint8)
"""
def __init__(self, env: gymnasium.Env, keep_dim: bool = False):
def __init__(self, env: gym.Env, keep_dim: bool = False):
"""Convert the image observation from RGB to gray scale.
Args:

View File

@@ -1,11 +1,11 @@
"""A wrapper that adds human-renering functionality to an environment."""
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.error import DependencyNotInstalled
class HumanRendering(gymnasium.Wrapper):
class HumanRendering(gym.Wrapper):
"""Performs human rendering for an environment that only supports "rgb_array"rendering.
This wrapper is particularly useful when you have implemented an environment that can produce
@@ -16,7 +16,7 @@ class HumanRendering(gymnasium.Wrapper):
The ``render_mode`` of the wrapped environment must be either ``'rgb_array'`` or ``'rgb_array_list'``.
Example:
>>> env = gymnasium.make("LunarLander-v2", render_mode="rgb_array")
>>> env = gym.make("LunarLander-v2", render_mode="rgb_array")
>>> wrapped = HumanRendering(env)
>>> wrapped.reset() # This will start rendering to the screen
@@ -25,13 +25,13 @@ class HumanRendering(gymnasium.Wrapper):
implement human-rendering natively (i.e. ``render_mode`` does not contain ``"human"``).
Example:
>>> env = gymnasium.make("NoNativeRendering-v2", render_mode="human") # NoNativeRendering-v0 doesn't implement human-rendering natively
>>> env = gym.make("NoNativeRendering-v2", render_mode="human") # NoNativeRendering-v0 doesn't implement human-rendering natively
>>> env.reset() # This will start rendering to the screen
Warning: If the base environment uses ``render_mode="rgb_array_list"``, its (i.e. the *base environment's*) render method
will always return an empty list:
>>> env = gymnasium.make("LunarLander-v2", render_mode="rgb_array_list")
>>> env = gym.make("LunarLander-v2", render_mode="rgb_array_list")
>>> wrapped = HumanRendering(env)
>>> wrapped.reset()
>>> env.render()

View File

@@ -1,7 +1,7 @@
"""Set of wrappers for normalizing actions and observations."""
import numpy as np
import gymnasium
import gymnasium as gym
class RunningMeanStd:
@@ -45,7 +45,7 @@ def update_mean_var_count_from_moments(
return new_mean, new_var, new_count
class NormalizeObservation(gymnasium.core.Wrapper):
class NormalizeObservation(gym.Wrapper):
"""This wrapper will normalize observations s.t. each coordinate is centered with unit variance.
Note:
@@ -53,7 +53,7 @@ class NormalizeObservation(gymnasium.core.Wrapper):
newly instantiated or the policy was changed recently.
"""
def __init__(self, env: gymnasium.Env, epsilon: float = 1e-8):
def __init__(self, env: gym.Env, epsilon: float = 1e-8):
"""This wrapper will normalize observations s.t. each coordinate is centered with unit variance.
Args:
@@ -93,7 +93,7 @@ class NormalizeObservation(gymnasium.core.Wrapper):
return (obs - self.obs_rms.mean) / np.sqrt(self.obs_rms.var + self.epsilon)
class NormalizeReward(gymnasium.core.Wrapper):
class NormalizeReward(gym.Wrapper):
r"""This wrapper will normalize immediate rewards s.t. their exponential moving average has a fixed variance.
The exponential moving average will have variance :math:`(1 - \gamma)^2`.
@@ -105,7 +105,7 @@ class NormalizeReward(gymnasium.core.Wrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
gamma: float = 0.99,
epsilon: float = 1e-8,
):

View File

@@ -1,9 +1,9 @@
"""Wrapper to enforce the proper ordering of environment operations."""
import gymnasium
import gymnasium as gym
from gymnasium.error import ResetNeeded
class OrderEnforcing(gymnasium.Wrapper):
class OrderEnforcing(gym.Wrapper):
"""A wrapper that will produce an error if :meth:`step` is called before an initial :meth:`reset`.
Example:
@@ -19,9 +19,7 @@ class OrderEnforcing(gymnasium.Wrapper):
>>> env.step(0)
"""
def __init__(
self, env: gymnasium.Env, disable_render_order_enforcing: bool = False
):
def __init__(self, env: gym.Env, disable_render_order_enforcing: bool = False):
"""A wrapper that will produce an error if :meth:`step` is called before an initial :meth:`reset`.
Args:

View File

@@ -6,13 +6,13 @@ from typing import Any, Dict, List, Optional, Tuple
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
STATE_KEY = "state"
class PixelObservationWrapper(gymnasium.ObservationWrapper):
class PixelObservationWrapper(gym.ObservationWrapper):
"""Augment observations by pixel values.
Observations of this wrapper will be dictionaries of images.
@@ -23,14 +23,14 @@ class PixelObservationWrapper(gymnasium.ObservationWrapper):
space) will be added to the dictionary under the key "state".
Example:
>>> import gymnasium
>>> env = PixelObservationWrapper(gymnasium.make('CarRacing-v1', render_mode="rgb_array"))
>>> import gymnasium as gym
>>> env = PixelObservationWrapper(gym.make('CarRacing-v1', render_mode="rgb_array"))
>>> obs = env.reset()
>>> obs.keys()
odict_keys(['pixels'])
>>> obs['pixels'].shape
(400, 600, 3)
>>> env = PixelObservationWrapper(gymnasium.make('CarRacing-v1', render_mode="rgb_array"), pixels_only=False)
>>> env = PixelObservationWrapper(gym.make('CarRacing-v1', render_mode="rgb_array"), pixels_only=False)
>>> obs = env.reset()
>>> obs.keys()
odict_keys(['state', 'pixels'])
@@ -38,7 +38,7 @@ class PixelObservationWrapper(gymnasium.ObservationWrapper):
(96, 96, 3)
>>> obs['pixels'].shape
(400, 600, 3)
>>> env = PixelObservationWrapper(gymnasium.make('CarRacing-v1', render_mode="rgb_array"), pixel_keys=('obs',))
>>> env = PixelObservationWrapper(gym.make('CarRacing-v1', render_mode="rgb_array"), pixel_keys=('obs',))
>>> obs = env.reset()
>>> obs.keys()
odict_keys(['obs'])
@@ -48,7 +48,7 @@ class PixelObservationWrapper(gymnasium.ObservationWrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
pixels_only: bool = True,
render_kwargs: Optional[Dict[str, Dict[str, Any]]] = None,
pixel_keys: Tuple[str, ...] = ("pixels",),

View File

@@ -5,7 +5,7 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
def add_vector_episode_statistics(
@@ -37,7 +37,7 @@ def add_vector_episode_statistics(
return info
class RecordEpisodeStatistics(gymnasium.Wrapper):
class RecordEpisodeStatistics(gym.Wrapper):
"""This wrapper will keep track of cumulative rewards and episode lengths.
At the end of an episode, the statistics of the episode will be added to ``info``
@@ -76,7 +76,7 @@ class RecordEpisodeStatistics(gymnasium.Wrapper):
length_queue: The lengths of the last ``deque_size``-many episodes
"""
def __init__(self, env: gymnasium.Env, deque_size: int = 100):
def __init__(self, env: gym.Env, deque_size: int = 100):
"""This wrapper will keep track of cumulative rewards and episode lengths.
Args:

View File

@@ -2,7 +2,7 @@
import os
from typing import Callable, Optional
import gymnasium
import gymnasium as gym
from gymnasium import logger
from gymnasium.wrappers.monitoring import video_recorder
@@ -24,7 +24,7 @@ def capped_cubic_video_schedule(episode_id: int) -> bool:
return episode_id % 1000 == 0
class RecordVideo(gymnasium.Wrapper):
class RecordVideo(gym.Wrapper):
"""This wrapper records videos of rollouts.
Usually, you only want to record episodes intermittently, say every hundredth episode.
@@ -39,7 +39,7 @@ class RecordVideo(gymnasium.Wrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
video_folder: str,
episode_trigger: Callable[[int], bool] = None,
step_trigger: Callable[[int], bool] = None,

View File

@@ -1,13 +1,11 @@
"""A wrapper that adds render collection mode to an environment."""
import gymnasium
import gymnasium as gym
class RenderCollection(gymnasium.Wrapper):
class RenderCollection(gym.Wrapper):
"""Save collection of render frames."""
def __init__(
self, env: gymnasium.Env, pop_frames: bool = True, reset_clean: bool = True
):
def __init__(self, env: gym.Env, pop_frames: bool = True, reset_clean: bool = True):
"""Initialize a :class:`RenderCollection` instance.
Args:

View File

@@ -3,19 +3,19 @@ from typing import Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium import spaces
class RescaleAction(gymnasium.ActionWrapper):
class RescaleAction(gym.ActionWrapper):
"""Affinely rescales the continuous action space of the environment to the range [min_action, max_action].
The base environment :attr:`env` must have an action space of type :class:`spaces.Box`. If :attr:`min_action`
or :attr:`max_action` are numpy arrays, the shape must match the shape of the environment's action space.
Example:
>>> import gymnasium
>>> env = gymnasium.make('BipedalWalker-v3')
>>> import gymnasium as gym
>>> env = gym.make('BipedalWalker-v3')
>>> env.action_space
Box(-1.0, 1.0, (4,), float32)
>>> min_action = -0.5
@@ -23,13 +23,13 @@ class RescaleAction(gymnasium.ActionWrapper):
>>> env = RescaleAction(env, min_action=min_action, max_action=max_action)
>>> env.action_space
Box(-0.5, [0. 0.5 1. 0.75], (4,), float32)
>>> RescaleAction(env, min_action, max_action).action_space == gymnasium.spaces.Box(min_action, max_action)
>>> RescaleAction(env, min_action, max_action).action_space == gym.spaces.Box(min_action, max_action)
True
"""
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
min_action: Union[float, int, np.ndarray],
max_action: Union[float, int, np.ndarray],
):

View File

@@ -3,12 +3,12 @@ from typing import Union
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.error import DependencyNotInstalled
from gymnasium.spaces import Box
class ResizeObservation(gymnasium.ObservationWrapper):
class ResizeObservation(gym.ObservationWrapper):
"""Resize the image observation.
This wrapper works on environments with image observations (or more generally observations of shape AxBxC) and resizes
@@ -16,8 +16,8 @@ class ResizeObservation(gymnasium.ObservationWrapper):
In that case, the observation is scaled to a square of side-length :attr:`shape`.
Example:
>>> import gymnasium
>>> env = gymnasium.make('CarRacing-v1')
>>> import gymnasium as gym
>>> env = gym.make('CarRacing-v1')
>>> env.observation_space.shape
(96, 96, 3)
>>> env = ResizeObservation(env, 64)
@@ -25,7 +25,7 @@ class ResizeObservation(gymnasium.ObservationWrapper):
(64, 64, 3)
"""
def __init__(self, env: gymnasium.Env, shape: Union[tuple, int]):
def __init__(self, env: gym.Env, shape: Union[tuple, int]):
"""Resizes image observations to shape given by :attr:`shape`.
Args:

View File

@@ -1,5 +1,5 @@
"""Implementation of StepAPICompatibility wrapper class for transforming envs between new and old step API."""
import gymnasium
import gymnasium as gym
from gymnasium.logger import deprecation
from gymnasium.utils.step_api_compatibility import (
convert_to_done_step_api,
@@ -7,7 +7,7 @@ from gymnasium.utils.step_api_compatibility import (
)
class StepAPICompatibility(gymnasium.Wrapper):
class StepAPICompatibility(gym.Wrapper):
r"""A wrapper which can transform an environment from new step API to old and vice-versa.
Old step API refers to step() method returning (observation, reward, done, info)
@@ -19,16 +19,16 @@ class StepAPICompatibility(gymnasium.Wrapper):
apply_step_compatibility (bool): Apply to convert environment to use new step API that returns two bools. (False by default)
Examples:
>>> env = gymnasium.make("CartPole-v1")
>>> env = gym.make("CartPole-v1")
>>> env # wrapper not applied by default, set to new API
<TimeLimit<OrderEnforcing<PassiveEnvChecker<CartPoleEnv<CartPole-v1>>>>>
>>> env = gymnasium.make("CartPole-v1", apply_api_compatibility=True) # set to old API
>>> env = gym.make("CartPole-v1", apply_api_compatibility=True) # set to old API
<StepAPICompatibility<TimeLimit<OrderEnforcing<PassiveEnvChecker<CartPoleEnv<CartPole-v1>>>>>>
>>> env = StepAPICompatibility(CustomEnv(), apply_step_compatibility=False) # manually using wrapper on unregistered envs
"""
def __init__(self, env: gymnasium.Env, output_truncation_bool: bool = True):
def __init__(self, env: gym.Env, output_truncation_bool: bool = True):
"""A wrapper which can transform an environment from new step API to old and vice-versa.
Args:

View File

@@ -1,19 +1,19 @@
"""Wrapper for adding time aware observations to environment observation."""
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box
class TimeAwareObservation(gymnasium.ObservationWrapper):
class TimeAwareObservation(gym.ObservationWrapper):
"""Augment the observation with the current time step in the episode.
The observation space of the wrapped environment is assumed to be a flat :class:`Box`.
In particular, pixel observations are not supported. This wrapper will append the current timestep within the current episode to the observation.
Example:
>>> import gymnasium
>>> env = gymnasium.make('CartPole-v1')
>>> import gymnasium as gym
>>> env = gym.make('CartPole-v1')
>>> env = TimeAwareObservation(env)
>>> env.reset()
array([ 0.03810719, 0.03522411, 0.02231044, -0.01088205, 0. ])
@@ -21,7 +21,7 @@ class TimeAwareObservation(gymnasium.ObservationWrapper):
array([ 0.03881167, -0.16021058, 0.0220928 , 0.28875574, 1. ])
"""
def __init__(self, env: gymnasium.Env):
def __init__(self, env: gym.Env):
"""Initialize :class:`TimeAwareObservation` that requires an environment with a flat :class:`Box` observation space.
Args:

View File

@@ -1,10 +1,10 @@
"""Wrapper for limiting the time steps of an environment."""
from typing import Optional
import gymnasium
import gymnasium as gym
class TimeLimit(gymnasium.Wrapper):
class TimeLimit(gym.Wrapper):
"""This wrapper will issue a `truncated` signal if a maximum number of timesteps is exceeded.
If a truncation is not defined inside the environment itself, this is the only place that the truncation signal is issued.
@@ -19,7 +19,7 @@ class TimeLimit(gymnasium.Wrapper):
def __init__(
self,
env: gymnasium.Env,
env: gym.Env,
max_episode_steps: Optional[int] = None,
):
"""Initializes the :class:`TimeLimit` wrapper with an environment and the number of steps after which truncation will occur.

View File

@@ -1,10 +1,10 @@
"""Wrapper for transforming observations."""
from typing import Any, Callable
import gymnasium
import gymnasium as gym
class TransformObservation(gymnasium.ObservationWrapper):
class TransformObservation(gym.ObservationWrapper):
"""Transform the observation via an arbitrary function :attr:`f`.
The function :attr:`f` should be defined on the observation space of the base environment, ``env``, and should, ideally, return values in the same space.
@@ -12,15 +12,15 @@ class TransformObservation(gymnasium.ObservationWrapper):
If the transformation you wish to apply to observations returns values in a *different* space, you should subclass :class:`ObservationWrapper`, implement the transformation, and set the new observation space accordingly. If you were to use this wrapper instead, the observation space would be set incorrectly.
Example:
>>> import gymnasium
>>> import gymnasium as gym
>>> import numpy as np
>>> env = gymnasium.make('CartPole-v1')
>>> env = gym.make('CartPole-v1')
>>> env = TransformObservation(env, lambda obs: obs + 0.1*np.random.randn(*obs.shape))
>>> env.reset()
array([-0.08319338, 0.04635121, -0.07394746, 0.20877492])
"""
def __init__(self, env: gymnasium.Env, f: Callable[[Any], Any]):
def __init__(self, env: gym.Env, f: Callable[[Any], Any]):
"""Initialize the :class:`TransformObservation` wrapper with an environment and a transform function :param:`f`.
Args:

View File

@@ -1,7 +1,7 @@
"""Wrapper for transforming the reward."""
from typing import Callable
import gymnasium
import gymnasium as gym
from gymnasium import RewardWrapper
@@ -12,8 +12,8 @@ class TransformReward(RewardWrapper):
If the base environment specifies a reward range which is not invariant under :attr:`f`, the :attr:`reward_range` of the wrapped environment will be incorrect.
Example:
>>> import gymnasium
>>> env = gymnasium.make('CartPole-v1')
>>> import gymnasium as gym
>>> env = gym.make('CartPole-v1')
>>> env = TransformReward(env, lambda r: 0.01*r)
>>> env.reset()
>>> observation, reward, terminated, truncated, info = env.step(env.action_space.sample())
@@ -21,7 +21,7 @@ class TransformReward(RewardWrapper):
0.01
"""
def __init__(self, env: gymnasium.Env, f: Callable[[float], float]):
def __init__(self, env: gym.Env, f: Callable[[float], float]):
"""Initialize the :class:`TransformReward` wrapper with an environment and reward transform function :param:`f`.
Args:

View File

@@ -2,10 +2,10 @@
from typing import List
import gymnasium
import gymnasium as gym
class VectorListInfo(gymnasium.Wrapper):
class VectorListInfo(gym.Wrapper):
"""Converts infos of vectorized environments from dict to List[dict].
This wrapper converts the info format of a

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.envs.registration import EnvSpec
from tests.envs.utils import all_testing_initialised_envs, mujoco_testing_env_specs
@@ -59,7 +59,7 @@ DISCRETE_ENVS = list(
@pytest.mark.parametrize(
"env", DISCRETE_ENVS, ids=[env.spec.id for env in DISCRETE_ENVS]
)
def test_discrete_actions_out_of_bound(env: gymnasium.Env):
def test_discrete_actions_out_of_bound(env: gym.Env):
"""Test out of bound actions in Discrete action_space.
In discrete action_space environments, `out-of-bound`
@@ -88,7 +88,7 @@ OOB_VALUE = 100
@pytest.mark.parametrize("env", BOX_ENVS, ids=[env.spec.id for env in BOX_ENVS])
def test_box_actions_out_of_bound(env: gymnasium.Env):
def test_box_actions_out_of_bound(env: gym.Env):
"""Test out of bound actions in Box action_space.
Environments with Box actions spaces perform clipping inside `step`.
@@ -100,7 +100,7 @@ def test_box_actions_out_of_bound(env: gymnasium.Env):
"""
env.reset(seed=42)
oob_env = gymnasium.make(env.spec.id, disable_env_checker=True)
oob_env = gym.make(env.spec.id, disable_env_checker=True)
oob_env.reset(seed=42)
assert isinstance(env.action_space, spaces.Box)

View File

@@ -3,12 +3,12 @@ from typing import Any, Dict, Optional, Tuple
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Discrete
from gymnasium.wrappers.compatibility import EnvCompatibility, LegacyEnv
class LegacyEnvExplicit(LegacyEnv, gymnasium.Env):
class LegacyEnvExplicit(LegacyEnv, gym.Env):
"""Legacy env that explicitly implements the old API."""
observation_space = Discrete(1)
@@ -37,7 +37,7 @@ class LegacyEnvExplicit(LegacyEnv, gymnasium.Env):
pass
class LegacyEnvImplicit(gymnasium.Env):
class LegacyEnvImplicit(gym.Env):
"""Legacy env that implicitly implements the old API as a protocol."""
observation_space = Discrete(1)
@@ -95,12 +95,12 @@ def test_implicit():
def test_make_compatibility_in_spec():
gymnasium.register(
gym.register(
id="LegacyTestEnv-v0",
entry_point=LegacyEnvExplicit,
apply_api_compatibility=True,
)
env = gymnasium.make("LegacyTestEnv-v0", render_mode="rgb_array")
env = gym.make("LegacyTestEnv-v0", render_mode="rgb_array")
assert env.observation_space == Discrete(1)
assert env.action_space == Discrete(1)
assert env.reset() == (0, {})
@@ -110,12 +110,12 @@ def test_make_compatibility_in_spec():
assert isinstance(img, np.ndarray)
assert img.shape == (1, 1, 3) # type: ignore
env.close()
del gymnasium.envs.registration.registry["LegacyTestEnv-v0"]
del gym.envs.registration.registry["LegacyTestEnv-v0"]
def test_make_compatibility_in_make():
gymnasium.register(id="LegacyTestEnv-v0", entry_point=LegacyEnvExplicit)
env = gymnasium.make(
gym.register(id="LegacyTestEnv-v0", entry_point=LegacyEnvExplicit)
env = gym.make(
"LegacyTestEnv-v0", apply_api_compatibility=True, render_mode="rgb_array"
)
assert env.observation_space == Discrete(1)
@@ -127,4 +127,4 @@ def test_make_compatibility_in_make():
assert isinstance(img, np.ndarray)
assert img.shape == (1, 1, 3) # type: ignore
env.close()
del gymnasium.envs.registration.registry["LegacyTestEnv-v0"]
del gym.envs.registration.registry["LegacyTestEnv-v0"]

View File

@@ -3,7 +3,7 @@ from typing import Optional
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.envs.box2d import BipedalWalker
from gymnasium.envs.box2d.lunar_lander import demo_heuristic_lander
from gymnasium.envs.toy_text import TaxiEnv
@@ -12,7 +12,7 @@ from gymnasium.envs.toy_text.frozen_lake import generate_random_map
def test_lunar_lander_heuristics():
"""Tests the LunarLander environment by checking if the heuristic lander works."""
lunar_lander = gymnasium.make("LunarLander-v2", disable_env_checker=True)
lunar_lander = gym.make("LunarLander-v2", disable_env_checker=True)
total_reward = demo_heuristic_lander(lunar_lander, seed=1)
assert total_reward > 100
@@ -23,7 +23,7 @@ def test_carracing_domain_randomize():
CarRacing DomainRandomize should have different colours at every reset.
However, it should have same colours when `options={"randomize": False}` is given to reset.
"""
env = gymnasium.make("CarRacing-v2", domain_randomize=True)
env = gym.make("CarRacing-v2", domain_randomize=True)
road_color = env.road_color
bg_color = env.bg_color
@@ -71,10 +71,8 @@ def test_bipedal_walker_hardcore_creation(seed: int):
HC_TERRAINS_COLOR1 = (255, 255, 255)
HC_TERRAINS_COLOR2 = (153, 153, 153)
env = gymnasium.make("BipedalWalker-v3", disable_env_checker=True).unwrapped
hc_env = gymnasium.make(
"BipedalWalkerHardcore-v3", disable_env_checker=True
).unwrapped
env = gym.make("BipedalWalker-v3", disable_env_checker=True).unwrapped
hc_env = gym.make("BipedalWalkerHardcore-v3", disable_env_checker=True).unwrapped
assert isinstance(env, BipedalWalker) and isinstance(hc_env, BipedalWalker)
assert env.hardcore is False and hc_env.hardcore is True
@@ -157,7 +155,7 @@ def test_taxi_encode_decode():
"low_high", [None, (-0.4, 0.4), (np.array(-0.4), np.array(0.4))]
)
def test_customizable_resets(env_name: str, low_high: Optional[list]):
env = gymnasium.make(env_name)
env = gym.make(env_name)
env.action_space.seed(0)
# First ensure we can do a reset.
if low_high is None:
@@ -180,7 +178,7 @@ def test_customizable_resets(env_name: str, low_high: Optional[list]):
],
)
def test_customizable_pendulum_resets(low_high: Optional[list]):
env = gymnasium.make("Pendulum-v1")
env = gym.make("Pendulum-v1")
env.action_space.seed(0)
# First ensure we can do a reset and the values are within expected ranges.
if low_high is None:
@@ -209,7 +207,7 @@ def test_customizable_pendulum_resets(low_high: Optional[list]):
],
)
def test_invalid_customizable_resets(env_name: str, low_high: list):
env = gymnasium.make(env_name)
env = gym.make(env_name)
low, high = low_high
with pytest.raises(ValueError):
# match=re.escape(f"Lower bound ({low}) must be lower than higher bound ({high}).")

View File

@@ -4,7 +4,7 @@ import warnings
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.envs.registration import EnvSpec
from gymnasium.logger import warn
from gymnasium.utils.env_checker import check_env, data_equivalence
@@ -48,7 +48,7 @@ def test_envs_pass_env_checker(spec):
for warning in caught_warnings:
if warning.message.args[0] not in CHECK_ENV_IGNORE_WARNINGS:
raise gymnasium.error.Error(f"Unexpected warning: {warning.message}")
raise gym.error.Error(f"Unexpected warning: {warning.message}")
# Note that this precludes running this test in multiple threads.
@@ -189,7 +189,7 @@ def test_render_modes(spec):
all_testing_initialised_envs,
ids=[env.spec.id for env in all_testing_initialised_envs],
)
def test_pickle_env(env: gymnasium.Env):
def test_pickle_env(env: gym.Env):
pickled_env = pickle.loads(pickle.dumps(env))
data_equivalence(env.reset(), pickled_env.reset())

View File

@@ -1,4 +1,4 @@
"""Tests that gymnasium.make works as expected."""
"""Tests that gym.make works as expected."""
import re
import warnings
@@ -7,7 +7,7 @@ from copy import deepcopy
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.envs.classic_control import cartpole
from gymnasium.wrappers import (
AutoResetWrapper,
@@ -22,12 +22,12 @@ from tests.envs.utils_envs import ArgumentEnv, RegisterDuringMakeEnv
from tests.testing_env import GenericTestEnv, old_step_fn
from tests.wrappers.utils import has_wrapper
gymnasium.register(
gym.register(
"RegisterDuringMakeEnv-v0",
entry_point="tests.envs.utils_envs:RegisterDuringMakeEnv",
)
gymnasium.register(
gym.register(
id="test.ArgumentEnv-v0",
entry_point="tests.envs.utils_envs:ArgumentEnv",
kwargs={
@@ -36,23 +36,23 @@ gymnasium.register(
},
)
gymnasium.register(
gym.register(
id="test/NoHuman-v0",
entry_point="tests.envs.utils_envs:NoHuman",
)
gymnasium.register(
gym.register(
id="test/NoHumanOldAPI-v0",
entry_point="tests.envs.utils_envs:NoHumanOldAPI",
)
gymnasium.register(
gym.register(
id="test/NoHumanNoRGB-v0",
entry_point="tests.envs.utils_envs:NoHumanNoRGB",
)
def test_make():
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
env = gym.make("CartPole-v1", disable_env_checker=True)
assert env.spec.id == "CartPole-v1"
assert isinstance(env.unwrapped, cartpole.CartPoleEnv)
env.close()
@@ -61,33 +61,32 @@ def test_make():
def test_make_deprecated():
with warnings.catch_warnings(record=True):
with pytest.raises(
gymnasium.error.Error,
gym.error.Error,
match=re.escape(
"Environment version v0 for `Humanoid` is deprecated. Please use `Humanoid-v4` instead."
),
):
gymnasium.make("Humanoid-v0", disable_env_checker=True)
gym.make("Humanoid-v0", disable_env_checker=True)
def test_make_max_episode_steps():
# Default, uses the spec's
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
env = gym.make("CartPole-v1", disable_env_checker=True)
assert has_wrapper(env, TimeLimit)
assert (
env.spec.max_episode_steps
== gymnasium.envs.registry["CartPole-v1"].max_episode_steps
env.spec.max_episode_steps == gym.envs.registry["CartPole-v1"].max_episode_steps
)
env.close()
# Custom max episode steps
env = gymnasium.make("CartPole-v1", max_episode_steps=100, disable_env_checker=True)
env = gym.make("CartPole-v1", max_episode_steps=100, disable_env_checker=True)
assert has_wrapper(env, TimeLimit)
assert env.spec.max_episode_steps == 100
env.close()
# Env spec has no max episode steps
assert gymnasium.spec("test.ArgumentEnv-v0").max_episode_steps is None
env = gymnasium.make(
assert gym.spec("test.ArgumentEnv-v0").max_episode_steps is None
env = gym.make(
"test.ArgumentEnv-v0", arg1=None, arg2=None, arg3=None, disable_env_checker=True
)
assert has_wrapper(env, TimeLimit) is False
@@ -95,57 +94,57 @@ def test_make_max_episode_steps():
def test_gym_make_autoreset():
"""Tests that `gymnasium.make` autoreset wrapper is applied only when `gymnasium.make(..., autoreset=True)`."""
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
"""Tests that `gym.make` autoreset wrapper is applied only when `gym.make(..., autoreset=True)`."""
env = gym.make("CartPole-v1", disable_env_checker=True)
assert has_wrapper(env, AutoResetWrapper) is False
env.close()
env = gymnasium.make("CartPole-v1", autoreset=False, disable_env_checker=True)
env = gym.make("CartPole-v1", autoreset=False, disable_env_checker=True)
assert has_wrapper(env, AutoResetWrapper) is False
env.close()
env = gymnasium.make("CartPole-v1", autoreset=True)
env = gym.make("CartPole-v1", autoreset=True)
assert has_wrapper(env, AutoResetWrapper)
env.close()
def test_make_disable_env_checker():
"""Tests that `gymnasium.make` disable env checker is applied only when `gymnasium.make(..., disable_env_checker=False)`."""
spec = deepcopy(gymnasium.spec("CartPole-v1"))
"""Tests that `gym.make` disable env checker is applied only when `gym.make(..., disable_env_checker=False)`."""
spec = deepcopy(gym.spec("CartPole-v1"))
# Test with spec disable env checker
spec.disable_env_checker = False
env = gymnasium.make(spec)
env = gym.make(spec)
assert has_wrapper(env, PassiveEnvChecker)
env.close()
# Test with overwritten spec using make disable env checker
assert spec.disable_env_checker is False
env = gymnasium.make(spec, disable_env_checker=True)
env = gym.make(spec, disable_env_checker=True)
assert has_wrapper(env, PassiveEnvChecker) is False
env.close()
# Test with spec enabled disable env checker
spec.disable_env_checker = True
env = gymnasium.make(spec)
env = gym.make(spec)
assert has_wrapper(env, PassiveEnvChecker) is False
env.close()
# Test with overwritten spec using make disable env checker
assert spec.disable_env_checker is True
env = gymnasium.make(spec, disable_env_checker=False)
env = gym.make(spec, disable_env_checker=False)
assert has_wrapper(env, PassiveEnvChecker)
env.close()
def test_apply_api_compatibility():
gymnasium.register(
gym.register(
"testing-old-env",
lambda: GenericTestEnv(step_fn=old_step_fn),
apply_api_compatibility=True,
max_episode_steps=3,
)
env = gymnasium.make("testing-old-env")
env = gym.make("testing-old-env")
env.reset()
assert len(env.step(env.action_space.sample())) == 5
@@ -153,11 +152,11 @@ def test_apply_api_compatibility():
_, _, termination, truncation, _ = env.step(env.action_space.sample())
assert termination is False and truncation is True
gymnasium.spec("testing-old-env").apply_api_compatibility = False
env = gymnasium.make("testing-old-env")
gym.spec("testing-old-env").apply_api_compatibility = False
env = gym.make("testing-old-env")
# Cannot run reset and step as will not work
env = gymnasium.make("testing-old-env", apply_api_compatibility=True)
env = gym.make("testing-old-env", apply_api_compatibility=True)
env.reset()
assert len(env.step(env.action_space.sample())) == 5
@@ -165,7 +164,7 @@ def test_apply_api_compatibility():
_, _, termination, truncation, _ = env.step(env.action_space.sample())
assert termination is False and truncation is True
gymnasium.envs.registry.pop("testing-old-env")
gym.envs.registry.pop("testing-old-env")
@pytest.mark.parametrize(
@@ -173,7 +172,7 @@ def test_apply_api_compatibility():
)
def test_passive_checker_wrapper_warnings(spec):
with warnings.catch_warnings(record=True) as caught_warnings:
env = gymnasium.make(spec) # disable_env_checker=False
env = gym.make(spec) # disable_env_checker=False
env.reset()
env.step(env.action_space.sample())
# todo, add check for render, bugged due to mujoco v2/3 and v4 envs
@@ -182,37 +181,37 @@ def test_passive_checker_wrapper_warnings(spec):
for warning in caught_warnings:
if warning.message.args[0] not in PASSIVE_CHECK_IGNORE_WARNING:
raise gymnasium.error.Error(f"Unexpected warning: {warning.message}")
raise gym.error.Error(f"Unexpected warning: {warning.message}")
def test_make_order_enforcing():
"""Checks that gymnasium.make wrappers the environment with the OrderEnforcing wrapper."""
"""Checks that gym.make wrappers the environment with the OrderEnforcing wrapper."""
assert all(spec.order_enforce is True for spec in all_testing_env_specs)
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
env = gym.make("CartPole-v1", disable_env_checker=True)
assert has_wrapper(env, OrderEnforcing)
# We can assume that there all other specs will also have the order enforcing
env.close()
gymnasium.register(
gym.register(
id="test.OrderlessArgumentEnv-v0",
entry_point="tests.envs.utils_envs:ArgumentEnv",
order_enforce=False,
kwargs={"arg1": None, "arg2": None, "arg3": None},
)
env = gymnasium.make("test.OrderlessArgumentEnv-v0", disable_env_checker=True)
env = gym.make("test.OrderlessArgumentEnv-v0", disable_env_checker=True)
assert has_wrapper(env, OrderEnforcing) is False
env.close()
def test_make_render_mode():
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
env = gym.make("CartPole-v1", disable_env_checker=True)
assert env.render_mode is None
env.close()
# Make sure that render_mode is applied correctly
env = gymnasium.make(
env = gym.make(
"CartPole-v1", render_mode="rgb_array_list", disable_env_checker=True
)
assert env.render_mode == "rgb_array_list"
@@ -224,24 +223,24 @@ def test_make_render_mode():
assert isinstance(renders[0], np.ndarray)
env.close()
env = gymnasium.make("CartPole-v1", render_mode=None, disable_env_checker=True)
env = gym.make("CartPole-v1", render_mode=None, disable_env_checker=True)
assert env.render_mode is None
valid_render_modes = env.metadata["render_modes"]
env.close()
assert len(valid_render_modes) > 0
with warnings.catch_warnings(record=True) as caught_warnings:
env = gymnasium.make(
env = gym.make(
"CartPole-v1", render_mode=valid_render_modes[0], disable_env_checker=True
)
assert env.render_mode == valid_render_modes[0]
env.close()
for warning in caught_warnings:
raise gymnasium.error.Error(f"Unexpected warning: {warning.message}")
raise gym.error.Error(f"Unexpected warning: {warning.message}")
# Make sure that native rendering is used when possible
env = gymnasium.make("CartPole-v1", render_mode="human", disable_env_checker=True)
env = gym.make("CartPole-v1", render_mode="human", disable_env_checker=True)
assert not has_wrapper(env, HumanRendering) # Should use native human-rendering
assert env.render_mode == "human"
env.close()
@@ -253,7 +252,7 @@ def test_make_render_mode():
),
):
# Make sure that `HumanRendering` is applied here
env = gymnasium.make(
env = gym.make(
"test/NoHuman-v0", render_mode="human", disable_env_checker=True
) # This environment doesn't use native rendering
assert has_wrapper(env, HumanRendering)
@@ -263,7 +262,7 @@ def test_make_render_mode():
with pytest.raises(
TypeError, match=re.escape("got an unexpected keyword argument 'render_mode'")
):
gymnasium.make(
gym.make(
"test/NoHumanOldAPI-v0",
render_mode="rgb_array_list",
disable_env_checker=True,
@@ -272,12 +271,12 @@ def test_make_render_mode():
# Make sure that an additional error is thrown a user tries to use the wrapper on an environment with old API
with warnings.catch_warnings(record=True):
with pytest.raises(
gymnasium.error.Error,
gym.error.Error,
match=re.escape(
"You passed render_mode='human' although test/NoHumanOldAPI-v0 doesn't implement human-rendering natively."
),
):
gymnasium.make(
gym.make(
"test/NoHumanOldAPI-v0", render_mode="human", disable_env_checker=True
)
@@ -288,11 +287,11 @@ def test_make_render_mode():
TypeError,
match=re.escape("got an unexpected keyword argument 'render'"),
):
gymnasium.make("CarRacing-v2", render="human")
gym.make("CarRacing-v2", render="human")
def test_make_kwargs():
env = gymnasium.make(
env = gym.make(
"test.ArgumentEnv-v0",
arg2="override_arg2",
arg3="override_arg3",
@@ -308,7 +307,7 @@ def test_make_kwargs():
def test_import_module_during_make():
# Test custom environment which is registered at make
env = gymnasium.make(
env = gym.make(
"tests.envs.utils:RegisterDuringMakeEnv-v0",
disable_env_checker=True,
)

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import envs
from gymnasium.envs.registration import EnvSpec
from tests.envs.utils import mujoco_testing_env_specs
@@ -105,7 +105,7 @@ def test_obs_space_mujoco_environments(env_spec: EnvSpec):
MUJOCO_V2_V3_ENVS = [
spec.name
for spec in mujoco_testing_env_specs
if spec.version == 2 and f"{spec.name}-v3" in gymnasium.envs.registry
if spec.version == 2 and f"{spec.name}-v3" in gym.envs.registry
]

View File

@@ -4,7 +4,7 @@ from typing import Optional
import pytest
import gymnasium
import gymnasium as gym
@pytest.fixture(scope="function")
@@ -16,7 +16,7 @@ def register_testing_envs():
versions = [1, 3, 5]
for version in versions:
env_id = f"{namespace}/{versioned_name}-v{version}"
gymnasium.register(
gym.register(
id=env_id,
entry_point="tests.envs.utils_envs:ArgumentEnv",
kwargs={
@@ -25,7 +25,7 @@ def register_testing_envs():
"arg3": "arg3",
},
)
gymnasium.register(
gym.register(
id=f"{namespace}/{unversioned_name}",
entry_point="tests.env.utils_envs:ArgumentEnv",
kwargs={
@@ -39,8 +39,8 @@ def register_testing_envs():
for version in versions:
env_id = f"{namespace}/{versioned_name}-v{version}"
del gymnasium.envs.registry[env_id]
del gymnasium.envs.registry[f"{namespace}/{unversioned_name}"]
del gym.envs.registry[env_id]
del gym.envs.registry[f"{namespace}/{unversioned_name}"]
@pytest.mark.parametrize(
@@ -63,8 +63,8 @@ def register_testing_envs():
def test_register(
env_id: str, namespace: Optional[str], name: str, version: Optional[int]
):
gymnasium.register(env_id, "no-entry-point")
assert gymnasium.spec(env_id).id == env_id
gym.register(env_id, "no-entry-point")
assert gym.spec(env_id).id == env_id
full_name = f"{name}"
if namespace:
@@ -72,9 +72,9 @@ def test_register(
if version is not None:
full_name = f"{full_name}-v{version}"
assert full_name in gymnasium.envs.registry.keys()
assert full_name in gym.envs.registry.keys()
del gymnasium.envs.registry[env_id]
del gym.envs.registry[env_id]
@pytest.mark.parametrize(
@@ -86,10 +86,8 @@ def test_register(
],
)
def test_register_error(env_id):
with pytest.raises(
gymnasium.error.Error, match=f"^Malformed environment ID: {env_id}"
):
gymnasium.register(env_id, "no-entry-point")
with pytest.raises(gym.error.Error, match=f"^Malformed environment ID: {env_id}"):
gym.register(env_id, "no-entry-point")
@pytest.mark.parametrize(
@@ -109,9 +107,9 @@ def test_register_error(env_id):
)
def test_env_suggestions(register_testing_envs, env_id_input, env_id_suggested):
with pytest.raises(
gymnasium.error.UnregisteredEnv, match=f"Did you mean: `{env_id_suggested}`?"
gym.error.UnregisteredEnv, match=f"Did you mean: `{env_id_suggested}`?"
):
gymnasium.make(env_id_input, disable_env_checker=True)
gym.make(env_id_input, disable_env_checker=True)
@pytest.mark.parametrize(
@@ -130,49 +128,49 @@ def test_env_version_suggestions(
):
if default_version:
with pytest.raises(
gymnasium.error.DeprecatedEnv,
gym.error.DeprecatedEnv,
match="It provides the default version", # env name,
):
gymnasium.make(env_id_input, disable_env_checker=True)
gym.make(env_id_input, disable_env_checker=True)
else:
with pytest.raises(
gymnasium.error.UnregisteredEnv,
gym.error.UnregisteredEnv,
match=f"It provides versioned environments: \\[ {suggested_versions} \\]",
):
gymnasium.make(env_id_input, disable_env_checker=True)
gym.make(env_id_input, disable_env_checker=True)
def test_register_versioned_unversioned():
# Register versioned then unversioned
versioned_env = "Test/MyEnv-v0"
gymnasium.register(versioned_env, "no-entry-point")
assert gymnasium.envs.spec(versioned_env).id == versioned_env
gym.register(versioned_env, "no-entry-point")
assert gym.envs.spec(versioned_env).id == versioned_env
unversioned_env = "Test/MyEnv"
with pytest.raises(
gymnasium.error.RegistrationError,
gym.error.RegistrationError,
match=re.escape(
"Can't register the unversioned environment `Test/MyEnv` when the versioned environment `Test/MyEnv-v0` of the same name already exists"
),
):
gymnasium.register(unversioned_env, "no-entry-point")
gym.register(unversioned_env, "no-entry-point")
# Clean everything
del gymnasium.envs.registry[versioned_env]
del gym.envs.registry[versioned_env]
# Register unversioned then versioned
gymnasium.register(unversioned_env, "no-entry-point")
assert gymnasium.envs.spec(unversioned_env).id == unversioned_env
gym.register(unversioned_env, "no-entry-point")
assert gym.envs.spec(unversioned_env).id == unversioned_env
with pytest.raises(
gymnasium.error.RegistrationError,
gym.error.RegistrationError,
match=re.escape(
"Can't register the versioned environment `Test/MyEnv-v0` when the unversioned environment `Test/MyEnv` of the same name already exists."
),
):
gymnasium.register(versioned_env, "no-entry-point")
gym.register(versioned_env, "no-entry-point")
# Clean everything
del gymnasium.envs.registry[unversioned_env]
del gym.envs.registry[unversioned_env]
def test_make_latest_versioned_env(register_testing_envs):
@@ -182,7 +180,7 @@ def test_make_latest_versioned_env(register_testing_envs):
"Using the latest versioned environment `MyAwesomeNamespace/MyAwesomeVersionedEnv-v5` instead of the unversioned environment `MyAwesomeNamespace/MyAwesomeVersionedEnv`."
),
):
env = gymnasium.make(
env = gym.make(
"MyAwesomeNamespace/MyAwesomeVersionedEnv", disable_env_checker=True
)
assert env.spec.id == "MyAwesomeNamespace/MyAwesomeVersionedEnv-v5"
@@ -190,11 +188,11 @@ def test_make_latest_versioned_env(register_testing_envs):
def test_namespace():
# Check if the namespace context manager works
with gymnasium.envs.registration.namespace("MyDefaultNamespace"):
gymnasium.register("MyDefaultEnvironment-v0", "no-entry-point")
gymnasium.register("MyDefaultEnvironment-v1", "no-entry-point")
assert "MyDefaultNamespace/MyDefaultEnvironment-v0" in gymnasium.envs.registry
assert "MyDefaultEnvironment-v1" in gymnasium.envs.registry
with gym.envs.registration.namespace("MyDefaultNamespace"):
gym.register("MyDefaultEnvironment-v0", "no-entry-point")
gym.register("MyDefaultEnvironment-v1", "no-entry-point")
assert "MyDefaultNamespace/MyDefaultEnvironment-v0" in gym.envs.registry
assert "MyDefaultEnvironment-v1" in gym.envs.registry
del gymnasium.envs.registry["MyDefaultNamespace/MyDefaultEnvironment-v0"]
del gymnasium.envs.registry["MyDefaultEnvironment-v1"]
del gym.envs.registry["MyDefaultNamespace/MyDefaultEnvironment-v0"]
del gym.envs.registry["MyDefaultEnvironment-v1"]

View File

@@ -1,92 +1,92 @@
"""Tests that gymnasium.spec works as expected."""
"""Tests that gym.spec works as expected."""
import re
import pytest
import gymnasium
import gymnasium as gym
def test_spec():
spec = gymnasium.spec("CartPole-v1")
spec = gym.spec("CartPole-v1")
assert spec.id == "CartPole-v1"
assert spec is gymnasium.envs.registry["CartPole-v1"]
assert spec is gym.envs.registry["CartPole-v1"]
def test_spec_kwargs():
map_name_value = "8x8"
env = gymnasium.make("FrozenLake-v1", map_name=map_name_value)
env = gym.make("FrozenLake-v1", map_name=map_name_value)
assert env.spec.kwargs["map_name"] == map_name_value
def test_spec_missing_lookup():
gymnasium.register(id="Test1-v0", entry_point="no-entry-point")
gymnasium.register(id="Test1-v15", entry_point="no-entry-point")
gymnasium.register(id="Test1-v9", entry_point="no-entry-point")
gymnasium.register(id="Other1-v100", entry_point="no-entry-point")
gym.register(id="Test1-v0", entry_point="no-entry-point")
gym.register(id="Test1-v15", entry_point="no-entry-point")
gym.register(id="Test1-v9", entry_point="no-entry-point")
gym.register(id="Other1-v100", entry_point="no-entry-point")
with pytest.raises(
gymnasium.error.DeprecatedEnv,
gym.error.DeprecatedEnv,
match=re.escape(
"Environment version v1 for `Test1` is deprecated. Please use `Test1-v15` instead."
),
):
gymnasium.spec("Test1-v1")
gym.spec("Test1-v1")
with pytest.raises(
gymnasium.error.UnregisteredEnv,
gym.error.UnregisteredEnv,
match=re.escape(
"Environment version `v1000` for environment `Test1` doesn't exist. It provides versioned environments: [ `v0`, `v9`, `v15` ]."
),
):
gymnasium.spec("Test1-v1000")
gym.spec("Test1-v1000")
with pytest.raises(
gymnasium.error.UnregisteredEnv,
gym.error.UnregisteredEnv,
match=re.escape("Environment Unknown1 doesn't exist. "),
):
gymnasium.spec("Unknown1-v1")
gym.spec("Unknown1-v1")
def test_spec_malformed_lookup():
with pytest.raises(
gymnasium.error.Error,
gym.error.Error,
match=f'^{re.escape("Malformed environment ID: “Breakout-v0”.(Currently all IDs must be of the form [namespace/](env-name)-v(version). (namespace is optional))")}$',
):
gymnasium.spec("“Breakout-v0”")
gym.spec("“Breakout-v0”")
def test_spec_versioned_lookups():
gymnasium.register("test/Test2-v5", "no-entry-point")
gym.register("test/Test2-v5", "no-entry-point")
with pytest.raises(
gymnasium.error.VersionNotFound,
gym.error.VersionNotFound,
match=re.escape(
"Environment version `v9` for environment `test/Test2` doesn't exist. It provides versioned environments: [ `v5` ]."
),
):
gymnasium.spec("test/Test2-v9")
gym.spec("test/Test2-v9")
with pytest.raises(
gymnasium.error.DeprecatedEnv,
gym.error.DeprecatedEnv,
match=re.escape(
"Environment version v4 for `test/Test2` is deprecated. Please use `test/Test2-v5` instead."
),
):
gymnasium.spec("test/Test2-v4")
gym.spec("test/Test2-v4")
assert gymnasium.spec("test/Test2-v5") is not None
assert gym.spec("test/Test2-v5") is not None
def test_spec_default_lookups():
gymnasium.register("test/Test3", "no-entry-point")
gym.register("test/Test3", "no-entry-point")
with pytest.raises(
gymnasium.error.DeprecatedEnv,
gym.error.DeprecatedEnv,
match=re.escape(
"Environment version `v0` for environment `test/Test3` doesn't exist. It provides the default version test/Test3`."
),
):
gymnasium.spec("test/Test3-v0")
gym.spec("test/Test3-v0")
assert gymnasium.spec("test/Test3") is not None
assert gym.spec("test/Test3") is not None

View File

@@ -3,12 +3,12 @@ from typing import List, Optional
import numpy as np
import gymnasium
from gymnasium import error, logger
import gymnasium as gym
from gymnasium import logger
from gymnasium.envs.registration import EnvSpec
def try_make_env(env_spec: EnvSpec) -> Optional[gymnasium.Env]:
def try_make_env(env_spec: EnvSpec) -> Optional[gym.Env]:
"""Tries to make the environment showing if it is possible.
Warning the environments have no wrappers, including time limit and order enforcing.
@@ -17,16 +17,16 @@ def try_make_env(env_spec: EnvSpec) -> Optional[gymnasium.Env]:
if "gymnasium.envs." in env_spec.entry_point:
try:
return env_spec.make(disable_env_checker=True).unwrapped
except (ImportError, error.DependencyNotInstalled) as e:
except (ImportError, gym.error.DependencyNotInstalled) as e:
logger.warn(f"Not testing {env_spec.id} due to error: {e}")
return None
# Tries to make all environment to test with
all_testing_initialised_envs: List[Optional[gymnasium.Env]] = [
try_make_env(env_spec) for env_spec in gymnasium.envs.registry.values()
all_testing_initialised_envs: List[Optional[gym.Env]] = [
try_make_env(env_spec) for env_spec in gym.envs.registry.values()
]
all_testing_initialised_envs: List[gymnasium.Env] = [
all_testing_initialised_envs: List[gym.Env] = [
env for env in all_testing_initialised_envs if env is not None
]

View File

@@ -1,17 +1,17 @@
import gymnasium
import gymnasium as gym
class RegisterDuringMakeEnv(gymnasium.Env):
class RegisterDuringMakeEnv(gym.Env):
"""Used in `test_registration.py` to check if `env.make` can import and register an env"""
def __init__(self):
self.action_space = gymnasium.spaces.Discrete(1)
self.observation_space = gymnasium.spaces.Discrete(1)
self.action_space = gym.spaces.Discrete(1)
self.observation_space = gym.spaces.Discrete(1)
class ArgumentEnv(gymnasium.Env):
observation_space = gymnasium.spaces.Box(low=-1, high=1, shape=(1,))
action_space = gymnasium.spaces.Box(low=-1, high=1, shape=(1,))
class ArgumentEnv(gym.Env):
observation_space = gym.spaces.Box(low=-1, high=1, shape=(1,))
action_space = gym.spaces.Box(low=-1, high=1, shape=(1,))
def __init__(self, arg1, arg2, arg3):
self.arg1 = arg1
@@ -20,7 +20,7 @@ class ArgumentEnv(gymnasium.Env):
# Environments to test render_mode
class NoHuman(gymnasium.Env):
class NoHuman(gym.Env):
"""Environment that does not have human-rendering."""
metadata = {"render_modes": ["rgb_array_list"], "render_fps": 4}
@@ -30,7 +30,7 @@ class NoHuman(gymnasium.Env):
self.render_mode = render_mode
class NoHumanOldAPI(gymnasium.Env):
class NoHumanOldAPI(gym.Env):
"""Environment that does not have human-rendering."""
metadata = {"render_modes": ["rgb_array_list"], "render_fps": 4}
@@ -39,7 +39,7 @@ class NoHumanOldAPI(gymnasium.Env):
pass
class NoHumanNoRGB(gymnasium.Env):
class NoHumanNoRGB(gym.Env):
"""Environment that has neither human- nor rgb-rendering"""
metadata = {"render_modes": ["ascii"], "render_fps": 4}

View File

@@ -4,7 +4,7 @@ import warnings
import numpy as np
import pytest
import gymnasium.error
import gymnasium as gym
from gymnasium.spaces import Box
from gymnasium.spaces.box import get_inf
@@ -310,7 +310,7 @@ def test_sample_mask():
"""Box cannot have a mask applied."""
space = Box(0, 1)
with pytest.raises(
gymnasium.error.Error,
gym.error.Error,
match=re.escape("Box.sample cannot be provided a mask, actual value: "),
):
space.sample(mask=np.array([0, 1, 0], dtype=np.int8))

View File

@@ -3,12 +3,12 @@ import re
import numpy as np
import pytest
import gymnasium.spaces
import gymnasium as gym
def test_sample():
"""Tests the sequence sampling works as expects and the errors are correctly raised."""
space = gymnasium.spaces.Sequence(gymnasium.spaces.Box(0, 1))
space = gym.spaces.Sequence(gym.spaces.Box(0, 1))
# Test integer mask length
for length in range(4):

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium.spaces
import gymnasium as gym
from gymnasium.spaces import Box, Dict, Discrete, MultiBinary, Tuple
from gymnasium.utils.env_checker import data_equivalence
@@ -79,7 +79,7 @@ def test_seeds(space, seed, expected_len):
"space_fn",
[
lambda: Tuple(["abc"]),
lambda: Tuple([gymnasium.spaces.Box(0, 1), "abc"]),
lambda: Tuple([gym.spaces.Box(0, 1), "abc"]),
lambda: Tuple("abc"),
],
)
@@ -89,25 +89,19 @@ def test_bad_space_calls(space_fn):
def test_contains_promotion():
space = gymnasium.spaces.Tuple(
(gymnasium.spaces.Box(0, 1), gymnasium.spaces.Box(-1, 0, (2,)))
)
space = gym.spaces.Tuple((gym.spaces.Box(0, 1), gym.spaces.Box(-1, 0, (2,))))
assert (
np.array([0.0], dtype=np.float32),
np.array([0.0, 0.0], dtype=np.float32),
) in space
space = gymnasium.spaces.Tuple(
(gymnasium.spaces.Box(0, 1), gymnasium.spaces.Box(-1, 0, (1,)))
)
space = gym.spaces.Tuple((gym.spaces.Box(0, 1), gym.spaces.Box(-1, 0, (1,))))
assert np.array([[0.0], [0.0]], dtype=np.float32) in space
def test_bad_seed():
space = gymnasium.spaces.Tuple(
(gymnasium.spaces.Box(0, 1), gymnasium.spaces.Box(0, 1))
)
space = gym.spaces.Tuple((gym.spaces.Box(0, 1), gym.spaces.Box(0, 1)))
with pytest.raises(
TypeError,
match="Expected seed type: list, tuple, int or None, actual type: <class 'float'>",

View File

@@ -4,7 +4,7 @@ from typing import Optional
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box, Graph, utils
from gymnasium.utils.env_checker import data_equivalence
from tests.spaces.utils import TESTING_SPACES, TESTING_SPACES_IDS
@@ -56,7 +56,7 @@ TESTING_SPACES_EXPECTED_FLATDIMS = [
zip_longest(TESTING_SPACES, TESTING_SPACES_EXPECTED_FLATDIMS),
ids=TESTING_SPACES_IDS,
)
def test_flatdim(space: gymnasium.spaces.Space, flatdim: Optional[int]):
def test_flatdim(space: gym.spaces.Space, flatdim: Optional[int]):
"""Checks that the flattened dims of the space is equal to an expected value."""
if space.is_np_flattenable:
dim = utils.flatdim(space)
@@ -93,7 +93,7 @@ def test_flatten_space(space):
else:
assert isinstance(
space,
(gymnasium.spaces.Tuple, gymnasium.spaces.Dict, gymnasium.spaces.Sequence),
(gym.spaces.Tuple, gym.spaces.Dict, gym.spaces.Sequence),
)

View File

@@ -2,7 +2,7 @@
import types
from typing import Any, Dict, Optional, Tuple, Union
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.core import ActType, ObsType
from gymnasium.envs.registration import EnvSpec
@@ -36,7 +36,7 @@ def basic_render_fn(self):
# todo: change all testing environment to this generic class
class GenericTestEnv(gymnasium.Env):
class GenericTestEnv(gym.Env):
"""A generic testing environment for use in testing with modified environments are required."""
def __init__(

View File

@@ -6,7 +6,7 @@ from typing import Tuple, Union
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.core import ObsType
from gymnasium.utils.env_checker import (
@@ -23,8 +23,8 @@ from tests.testing_env import GenericTestEnv
@pytest.mark.parametrize(
"env",
[
gymnasium.make("CartPole-v1", disable_env_checker=True).unwrapped,
gymnasium.make("MountainCar-v0", disable_env_checker=True).unwrapped,
gym.make("CartPole-v1", disable_env_checker=True).unwrapped,
gym.make("MountainCar-v0", disable_env_checker=True).unwrapped,
GenericTestEnv(
observation_space=spaces.Dict(
a=spaces.Discrete(10), b=spaces.Box(np.zeros(2), np.ones(2))
@@ -80,7 +80,7 @@ def _reset_default_seed(self: GenericTestEnv, seed="Error", options=None):
"test,func,message",
[
[
gymnasium.error.Error,
gym.error.Error,
lambda self: (self.observation_space.sample(), {}),
"The `reset` method does not provide a `seed` or `**kwargs` keyword argument.",
],
@@ -231,7 +231,7 @@ def test_check_seed_deprecation():
def test_check_reset_options():
"""Tests the check_reset_options function."""
with pytest.raises(
gymnasium.error.Error,
gym.error.Error,
match=re.escape(
"The `reset` method does not provide an `options` or `**kwargs` keyword argument"
),
@@ -256,7 +256,7 @@ def test_check_reset_options():
],
],
)
def test_check_env(env: gymnasium.Env, message: str):
def test_check_env(env: gym.Env, message: str):
"""Tests the check_env function works as expected."""
with pytest.raises(AssertionError, match=f"^{re.escape(message)}$"):
check_env(env)

View File

@@ -5,7 +5,7 @@ from typing import Dict, Union
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.utils.passive_env_checker import (
check_action_space,
@@ -349,7 +349,7 @@ def _modified_step(
"Expects `truncated` signal to be a boolean, actual type: <class 'str'>",
],
[
gymnasium.error.Error,
gym.error.Error,
lambda self, _: (1, 2, 3),
"Expected `Env.step` to return a four or five element tuple, actual number of elements returned: 3.",
],

View File

@@ -8,7 +8,7 @@ import pytest
from pygame import KEYDOWN, KEYUP, QUIT, event
from pygame.event import Event
import gymnasium
import gymnasium as gym
from gymnasium.utils.play import MissingKeysToAction, PlayableGame, play
from tests.testing_env import GenericTestEnv
@@ -24,7 +24,7 @@ PlayableEnv = partial(
)
class KeysToActionWrapper(gymnasium.Wrapper):
class KeysToActionWrapper(gym.Wrapper):
def __init__(self, env, keys_to_action):
super().__init__(env)
self.keys_to_action = keys_to_action
@@ -175,7 +175,7 @@ def test_play_loop_real_env():
return obs_t, obs_tp1, action, rew, terminated, truncated, info
env = gymnasium.make(ENV, render_mode="rgb_array", disable_env_checker=True)
env = gym.make(ENV, render_mode="rgb_array", disable_env_checker=True)
env.reset(seed=SEED)
keys_to_action = (
dummy_keys_to_action_str() if str_keys else dummy_keys_to_action()
@@ -188,9 +188,7 @@ def test_play_loop_real_env():
action = keys_to_action[chr(e.key) if str_keys else (e.key,)]
obs, _, _, _, _ = env.step(action)
env_play = gymnasium.make(
ENV, render_mode="rgb_array", disable_env_checker=True
)
env_play = gym.make(ENV, render_mode="rgb_array", disable_env_checker=True)
if apply_wrapper:
env_play = KeysToActionWrapper(env, keys_to_action=keys_to_action)
assert hasattr(env_play, "get_keys_to_action")
@@ -208,4 +206,4 @@ def test_play_loop_real_env():
def test_play_no_keys():
with pytest.raises(MissingKeysToAction):
play(gymnasium.make("CartPole-v1"))
play(gym.make("CartPole-v1"))

View File

@@ -3,12 +3,12 @@ import shutil
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.utils.save_video import capped_cubic_video_schedule, save_video
def test_record_video_using_default_trigger():
env = gymnasium.make(
env = gym.make(
"CartPole-v1", render_mode="rgb_array_list", disable_env_checker=True
)
@@ -47,7 +47,7 @@ def modulo_step_trigger(mod: int):
def test_record_video_step_trigger():
env = gymnasium.make("CartPole-v1", render_mode="rgb_array_list")
env = gym.make("CartPole-v1", render_mode="rgb_array_list")
env._max_episode_steps = 20
env.reset()
@@ -81,7 +81,7 @@ def test_record_video_within_vector():
n_steps = 199
expected_video = 2
envs = gymnasium.vector.make(
envs = gym.vector.make(
"CartPole-v1", num_envs=2, asynchronous=True, render_mode="rgb_array_list"
)
envs.reset()

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.vector.sync_vector_env import SyncVectorEnv
from tests.vector.utils import make_env
@@ -13,7 +13,7 @@ SEED = 42
@pytest.mark.parametrize("asynchronous", [True, False])
def test_vector_env_info(asynchronous):
env = gymnasium.vector.make(
env = gym.vector.make(
ENV_ID, num_envs=NUM_ENVS, asynchronous=asynchronous, disable_env_checker=True
)
env.reset(seed=SEED)

View File

@@ -1,6 +1,6 @@
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.vector import AsyncVectorEnv, SyncVectorEnv
from gymnasium.wrappers import OrderEnforcing, TimeLimit, TransformObservation
from gymnasium.wrappers.env_checker import PassiveEnvChecker
@@ -8,7 +8,7 @@ from tests.wrappers.utils import has_wrapper
def test_vector_make_id():
env = gymnasium.vector.make("CartPole-v1")
env = gym.vector.make("CartPole-v1")
assert isinstance(env, AsyncVectorEnv)
assert env.num_envs == 1
env.close()
@@ -16,28 +16,28 @@ def test_vector_make_id():
@pytest.mark.parametrize("num_envs", [1, 3, 10])
def test_vector_make_num_envs(num_envs):
env = gymnasium.vector.make("CartPole-v1", num_envs=num_envs)
env = gym.vector.make("CartPole-v1", num_envs=num_envs)
assert env.num_envs == num_envs
env.close()
def test_vector_make_asynchronous():
env = gymnasium.vector.make("CartPole-v1", asynchronous=True)
env = gym.vector.make("CartPole-v1", asynchronous=True)
assert isinstance(env, AsyncVectorEnv)
env.close()
env = gymnasium.vector.make("CartPole-v1", asynchronous=False)
env = gym.vector.make("CartPole-v1", asynchronous=False)
assert isinstance(env, SyncVectorEnv)
env.close()
def test_vector_make_wrappers():
env = gymnasium.vector.make("CartPole-v1", num_envs=2, asynchronous=False)
env = gym.vector.make("CartPole-v1", num_envs=2, asynchronous=False)
assert isinstance(env, SyncVectorEnv)
assert len(env.envs) == 2
sub_env = env.envs[0]
assert isinstance(sub_env, gymnasium.Env)
assert isinstance(sub_env, gym.Env)
if sub_env.spec.order_enforce:
assert has_wrapper(sub_env, OrderEnforcing)
if sub_env.spec.max_episode_steps is not None:
@@ -48,7 +48,7 @@ def test_vector_make_wrappers():
)
env.close()
env = gymnasium.vector.make(
env = gym.vector.make(
"CartPole-v1",
num_envs=2,
asynchronous=False,
@@ -63,12 +63,12 @@ def test_vector_make_wrappers():
def test_vector_make_disable_env_checker():
# As asynchronous environment are inaccessible, synchronous vector must be used
env = gymnasium.vector.make("CartPole-v1", num_envs=1, asynchronous=False)
env = gym.vector.make("CartPole-v1", num_envs=1, asynchronous=False)
assert isinstance(env, SyncVectorEnv)
assert has_wrapper(env.envs[0], PassiveEnvChecker)
env.close()
env = gymnasium.vector.make("CartPole-v1", num_envs=5, asynchronous=False)
env = gym.vector.make("CartPole-v1", num_envs=5, asynchronous=False)
assert isinstance(env, SyncVectorEnv)
assert has_wrapper(env.envs[0], PassiveEnvChecker)
assert all(
@@ -76,7 +76,7 @@ def test_vector_make_disable_env_checker():
)
env.close()
env = gymnasium.vector.make(
env = gym.vector.make(
"CartPole-v1", num_envs=3, asynchronous=False, disable_env_checker=True
)
assert isinstance(env, SyncVectorEnv)

View File

@@ -3,7 +3,7 @@ from typing import Optional
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box, Dict, Discrete, MultiBinary, MultiDiscrete, Tuple
from gymnasium.utils.seeding import RandomNumberGenerator
@@ -50,7 +50,7 @@ spaces = [
HEIGHT, WIDTH = 64, 64
class UnittestSlowEnv(gymnasium.Env):
class UnittestSlowEnv(gym.Env):
def __init__(self, slow_reset=0.3):
super().__init__()
self.slow_reset = slow_reset
@@ -72,7 +72,7 @@ class UnittestSlowEnv(gymnasium.Env):
return observation, reward, terminated, truncated, {}
class CustomSpace(gymnasium.Space):
class CustomSpace(gym.Space):
"""Minimal custom observation space."""
def sample(self):
@@ -91,7 +91,7 @@ custom_spaces = [
]
class CustomSpaceEnv(gymnasium.Env):
class CustomSpaceEnv(gym.Env):
def __init__(self):
super().__init__()
self.observation_space = CustomSpace()
@@ -109,7 +109,7 @@ class CustomSpaceEnv(gymnasium.Env):
def make_env(env_name, seed, **kwargs):
def _make():
env = gymnasium.make(env_name, disable_env_checker=True, **kwargs)
env = gym.make(env_name, disable_env_checker=True, **kwargs)
env.action_space.seed(seed)
env.reset(seed=seed)
return env

View File

@@ -5,12 +5,12 @@ from unittest.mock import MagicMock
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import AutoResetWrapper
from tests.envs.utils import all_testing_env_specs
class DummyResetEnv(gymnasium.Env):
class DummyResetEnv(gym.Env):
"""A dummy environment which returns ascending numbers starting at `0` when :meth:`self.step()` is called.
After the second call to :meth:`self.step()` terminated is true.
@@ -22,10 +22,10 @@ class DummyResetEnv(gymnasium.Env):
def __init__(self):
"""Initialise the DummyResetEnv."""
self.action_space = gymnasium.spaces.Box(
self.action_space = gym.spaces.Box(
low=np.array([0]), high=np.array([2]), dtype=np.int64
)
self.observation_space = gymnasium.spaces.Discrete(2)
self.observation_space = gym.spaces.Discrete(2)
self.count = 0
def step(self, action: int):
@@ -45,9 +45,9 @@ class DummyResetEnv(gymnasium.Env):
return np.array([self.count]), {"count": self.count}
def unwrap_env(env) -> Generator[gymnasium.Wrapper, None, None]:
def unwrap_env(env) -> Generator[gym.Wrapper, None, None]:
"""Unwraps an environment yielding all wrappers around environment."""
while isinstance(env, gymnasium.Wrapper):
while isinstance(env, gym.Wrapper):
yield type(env)
env = env.env
@@ -56,14 +56,14 @@ def unwrap_env(env) -> Generator[gymnasium.Wrapper, None, None]:
"spec", all_testing_env_specs, ids=[spec.id for spec in all_testing_env_specs]
)
def test_make_autoreset_true(spec):
"""Tests gymnasium.make with `autoreset=True`, and check that the reset actually happens.
"""Tests gym.make with `autoreset=True`, and check that the reset actually happens.
Note: This test assumes that the outermost wrapper is AutoResetWrapper so if that
is being changed in the future, this test will break and need to be updated.
Note: This test assumes that all first-party environments will terminate in a finite
amount of time with random actions, which is true as of the time of adding this test.
"""
env = gymnasium.make(spec.id, autoreset=True, disable_env_checker=True)
env = gym.make(spec.id, autoreset=True, disable_env_checker=True)
assert AutoResetWrapper in unwrap_env(env)
env.reset(seed=0)
@@ -81,16 +81,16 @@ def test_make_autoreset_true(spec):
"spec", all_testing_env_specs, ids=[spec.id for spec in all_testing_env_specs]
)
def test_gym_make_autoreset(spec):
"""Tests that `gymnasium.make` autoreset wrapper is applied only when `gymnasium.make(..., autoreset=True)`."""
env = gymnasium.make(spec.id, disable_env_checker=True)
"""Tests that `gym.make` autoreset wrapper is applied only when `gym.make(..., autoreset=True)`."""
env = gym.make(spec.id, disable_env_checker=True)
assert AutoResetWrapper not in unwrap_env(env)
env.close()
env = gymnasium.make(spec.id, autoreset=False, disable_env_checker=True)
env = gym.make(spec.id, autoreset=False, disable_env_checker=True)
assert AutoResetWrapper not in unwrap_env(env)
env.close()
env = gymnasium.make(spec.id, autoreset=True, disable_env_checker=True)
env = gym.make(spec.id, autoreset=True, disable_env_checker=True)
assert AutoResetWrapper in unwrap_env(env)
env.close()

View File

@@ -1,14 +1,14 @@
import numpy as np
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import ClipAction
def test_clip_action():
# mountaincar: action-based rewards
env = gymnasium.make("MountainCarContinuous-v0", disable_env_checker=True)
env = gym.make("MountainCarContinuous-v0", disable_env_checker=True)
wrapped_env = ClipAction(
gymnasium.make("MountainCarContinuous-v0", disable_env_checker=True)
gym.make("MountainCarContinuous-v0", disable_env_checker=True)
)
seed = 0

View File

@@ -3,12 +3,12 @@ from typing import Optional, Tuple
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.wrappers.filter_observation import FilterObservation
class FakeEnvironment(gymnasium.Env):
class FakeEnvironment(gym.Env):
def __init__(
self, render_mode=None, observation_keys: Tuple[str, ...] = ("state",)
):

View File

@@ -6,12 +6,12 @@ from typing import Optional
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box, Dict, flatten, unflatten
from gymnasium.wrappers import FlattenObservation
class FakeEnvironment(gymnasium.Env):
class FakeEnvironment(gym.Env):
def __init__(self, observation_space):
self.observation_space = observation_space

View File

@@ -1,14 +1,14 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.wrappers import FlattenObservation
@pytest.mark.parametrize("env_id", ["Blackjack-v1"])
def test_flatten_observation(env_id):
env = gymnasium.make(env_id, disable_env_checker=True)
env = gym.make(env_id, disable_env_checker=True)
wrapped_env = FlattenObservation(env)
obs, info = env.reset()

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import FrameStack
try:
@@ -25,13 +25,13 @@ except ImportError:
],
)
def test_frame_stack(env_id, num_stack, lz4_compress):
env = gymnasium.make(env_id, disable_env_checker=True)
env = gym.make(env_id, disable_env_checker=True)
shape = env.observation_space.shape
env = FrameStack(env, num_stack, lz4_compress)
assert env.observation_space.shape == (num_stack,) + shape
assert env.observation_space.dtype == env.env.observation_space.dtype
dup = gymnasium.make(env_id, disable_env_checker=True)
dup = gym.make(env_id, disable_env_checker=True)
obs, _ = env.reset(seed=0)
dup_obs, _ = dup.reset(seed=0)

View File

@@ -1,6 +1,6 @@
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.wrappers import GrayScaleObservation
@@ -8,7 +8,7 @@ from gymnasium.wrappers import GrayScaleObservation
@pytest.mark.parametrize("env_id", ["CarRacing-v2"])
@pytest.mark.parametrize("keep_dim", [True, False])
def test_gray_scale_observation(env_id, keep_dim):
rgb_env = gymnasium.make(env_id, disable_env_checker=True)
rgb_env = gym.make(env_id, disable_env_checker=True)
assert isinstance(rgb_env.observation_space, spaces.Box)
assert len(rgb_env.observation_space.shape) == 3

View File

@@ -2,14 +2,14 @@ import re
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import HumanRendering
def test_human_rendering():
for mode in ["rgb_array", "rgb_array_list"]:
env = HumanRendering(
gymnasium.make("CartPole-v1", render_mode=mode, disable_env_checker=True)
gym.make("CartPole-v1", render_mode=mode, disable_env_checker=True)
)
assert env.render_mode == "human"
env.reset()
@@ -21,7 +21,7 @@ def test_human_rendering():
env.close()
env = gymnasium.make("CartPole-v1", render_mode="human")
env = gym.make("CartPole-v1", render_mode="human")
with pytest.raises(
AssertionError,
match=re.escape(

View File

@@ -4,12 +4,12 @@ from typing import Optional
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.spaces import Box, Dict, Tuple
from gymnasium.wrappers import FilterObservation, FlattenObservation
class FakeEnvironment(gymnasium.Env):
class FakeEnvironment(gym.Env):
def __init__(self, observation_space, render_mode=None):
self.observation_space = observation_space
self.obs_keys = self.observation_space.spaces.keys()

View File

@@ -3,16 +3,16 @@ from typing import Optional
import numpy as np
from numpy.testing import assert_almost_equal
import gymnasium
import gymnasium as gym
from gymnasium.wrappers.normalize import NormalizeObservation, NormalizeReward
class DummyRewardEnv(gymnasium.Env):
class DummyRewardEnv(gym.Env):
metadata = {}
def __init__(self, return_reward_idx=0):
self.action_space = gymnasium.spaces.Discrete(2)
self.observation_space = gymnasium.spaces.Box(
self.action_space = gym.spaces.Discrete(2)
self.observation_space = gym.spaces.Box(
low=np.array([-1.0]), high=np.array([1.0]), dtype=np.float64
)
self.returned_rewards = [0, 1, 2, 3, 4]
@@ -81,14 +81,14 @@ def test_normalize_return():
def test_normalize_observation_vector_env():
env_fns = [make_env(0), make_env(1)]
envs = gymnasium.vector.SyncVectorEnv(env_fns)
envs = gym.vector.SyncVectorEnv(env_fns)
envs.reset()
obs, reward, _, _, _ = envs.step(envs.action_space.sample())
np.testing.assert_almost_equal(obs, np.array([[1], [2]]), decimal=4)
np.testing.assert_almost_equal(reward, np.array([1, 2]), decimal=4)
env_fns = [make_env(0), make_env(1)]
envs = gymnasium.vector.SyncVectorEnv(env_fns)
envs = gym.vector.SyncVectorEnv(env_fns)
envs = NormalizeObservation(envs)
envs.reset()
assert_almost_equal(
@@ -106,7 +106,7 @@ def test_normalize_observation_vector_env():
def test_normalize_return_vector_env():
env_fns = [make_env(0), make_env(1)]
envs = gymnasium.vector.SyncVectorEnv(env_fns)
envs = gym.vector.SyncVectorEnv(env_fns)
envs = NormalizeReward(envs)
obs = envs.reset()
obs, reward, _, _, _ = envs.step(envs.action_space.sample())

View File

@@ -1,6 +1,6 @@
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.envs.classic_control import CartPoleEnv
from gymnasium.error import ResetNeeded
from gymnasium.wrappers import OrderEnforcing
@@ -12,15 +12,15 @@ from tests.wrappers.utils import has_wrapper
"spec", all_testing_env_specs, ids=[spec.id for spec in all_testing_env_specs]
)
def test_gym_make_order_enforcing(spec):
"""Checks that gymnasium.make wrappers the environment with the OrderEnforcing wrapper."""
env = gymnasium.make(spec.id, disable_env_checker=True)
"""Checks that gym.make wrappers the environment with the OrderEnforcing wrapper."""
env = gym.make(spec.id, disable_env_checker=True)
assert has_wrapper(env, OrderEnforcing)
def test_order_enforcing():
"""Checks that the order enforcing works as expected, raising an error before reset is called and not after."""
# The reason for not using gymnasium.make is that all environments are by default wrapped in the order enforcing wrapper
# The reason for not using gym.make is that all environments are by default wrapped in the order enforcing wrapper
env = CartPoleEnv(render_mode="rgb_array_list")
assert not has_wrapper(env, OrderEnforcing)

View File

@@ -4,7 +4,7 @@ import warnings
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.wrappers.env_checker import PassiveEnvChecker
from tests.envs.test_envs import PASSIVE_CHECK_IGNORE_WARNING
from tests.envs.utils import all_testing_initialised_envs
@@ -27,7 +27,7 @@ def test_passive_checker_wrapper_warnings(env):
for warning in caught_warnings:
if warning.message.args[0] not in PASSIVE_CHECK_IGNORE_WARNING:
raise gymnasium.error.Error(f"Unexpected warning: {warning.message}")
raise gym.error.Error(f"Unexpected warning: {warning.message}")
@pytest.mark.parametrize(

View File

@@ -4,12 +4,12 @@ from typing import Optional
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium import spaces
from gymnasium.wrappers.pixel_observation import STATE_KEY, PixelObservationWrapper
class FakeEnvironment(gymnasium.Env):
class FakeEnvironment(gym.Env):
def __init__(self, render_mode="single_rgb_array"):
self.action_space = spaces.Box(shape=(1,), low=-1, high=1, dtype=np.float32)
self.render_mode = render_mode

View File

@@ -1,7 +1,7 @@
import numpy as np
import pytest
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import RecordEpisodeStatistics, VectorListInfo
from gymnasium.wrappers.record_episode_statistics import add_vector_episode_statistics
@@ -9,7 +9,7 @@ from gymnasium.wrappers.record_episode_statistics import add_vector_episode_stat
@pytest.mark.parametrize("env_id", ["CartPole-v1", "Pendulum-v1"])
@pytest.mark.parametrize("deque_size", [2, 5])
def test_record_episode_statistics(env_id, deque_size):
env = gymnasium.make(env_id, disable_env_checker=True)
env = gym.make(env_id, disable_env_checker=True)
env = RecordEpisodeStatistics(env, deque_size)
for n in range(5):
@@ -28,7 +28,7 @@ def test_record_episode_statistics(env_id, deque_size):
def test_record_episode_statistics_reset_info():
env = gymnasium.make("CartPole-v1", disable_env_checker=True)
env = gym.make("CartPole-v1", disable_env_checker=True)
env = RecordEpisodeStatistics(env)
ob_space = env.observation_space
obs, info = env.reset()
@@ -40,7 +40,7 @@ def test_record_episode_statistics_reset_info():
("num_envs", "asynchronous"), [(1, False), (1, True), (4, False), (4, True)]
)
def test_record_episode_statistics_with_vectorenv(num_envs, asynchronous):
envs = gymnasium.vector.make(
envs = gym.vector.make(
"CartPole-v1",
render_mode=None,
num_envs=num_envs,
@@ -68,7 +68,7 @@ def test_record_episode_statistics_with_vectorenv(num_envs, asynchronous):
def test_wrong_wrapping_order():
envs = gymnasium.vector.make("CartPole-v1", num_envs=3, disable_env_checker=True)
envs = gym.vector.make("CartPole-v1", num_envs=3, disable_env_checker=True)
wrapped_env = RecordEpisodeStatistics(VectorListInfo(envs))
wrapped_env.reset()

View File

@@ -1,15 +1,15 @@
import os
import shutil
import gymnasium
import gymnasium as gym
from gymnasium.wrappers import capped_cubic_video_schedule
def test_record_video_using_default_trigger():
env = gymnasium.make(
env = gym.make(
"CartPole-v1", render_mode="rgb_array_list", disable_env_checker=True
)
env = gymnasium.wrappers.RecordVideo(env, "videos")
env = gym.wrappers.RecordVideo(env, "videos")
env.reset()
for _ in range(199):
action = env.action_space.sample()
@@ -26,12 +26,8 @@ def test_record_video_using_default_trigger():
def test_record_video_reset():
env = gymnasium.make(
"CartPole-v1", render_mode="rgb_array", disable_env_checker=True
)
env = gymnasium.wrappers.RecordVideo(
env, "videos", step_trigger=lambda x: x % 100 == 0
)
env = gym.make("CartPole-v1", render_mode="rgb_array", disable_env_checker=True)
env = gym.wrappers.RecordVideo(env, "videos", step_trigger=lambda x: x % 100 == 0)
ob_space = env.observation_space
obs, info = env.reset()
env.close()
@@ -42,13 +38,9 @@ def test_record_video_reset():
def test_record_video_step_trigger():
env = gymnasium.make(
"CartPole-v1", render_mode="rgb_array", disable_env_checker=True
)
env = gym.make("CartPole-v1", render_mode="rgb_array", disable_env_checker=True)
env._max_episode_steps = 20
env = gymnasium.wrappers.RecordVideo(
env, "videos", step_trigger=lambda x: x % 100 == 0
)
env = gym.wrappers.RecordVideo(env, "videos", step_trigger=lambda x: x % 100 == 0)
env.reset()
for _ in range(199):
action = env.action_space.sample()
@@ -64,10 +56,10 @@ def test_record_video_step_trigger():
def make_env(gym_id, seed, **kwargs):
def thunk():
env = gymnasium.make(gym_id, disable_env_checker=True, **kwargs)
env = gym.make(gym_id, disable_env_checker=True, **kwargs)
env._max_episode_steps = 20
if seed == 1:
env = gymnasium.wrappers.RecordVideo(
env = gym.wrappers.RecordVideo(
env, "videos", step_trigger=lambda x: x % 100 == 0
)
return env
@@ -76,10 +68,10 @@ def make_env(gym_id, seed, **kwargs):
def test_record_video_within_vector():
envs = gymnasium.vector.SyncVectorEnv(
envs = gym.vector.SyncVectorEnv(
[make_env("CartPole-v1", 1 + i, render_mode="rgb_array") for i in range(2)]
)
envs = gymnasium.wrappers.RecordEpisodeStatistics(envs)
envs = gym.wrappers.RecordEpisodeStatistics(envs)
envs.reset()
for i in range(199):
_, _, _, _, infos = envs.step(envs.action_space.sample())

Some files were not shown because too many files have changed in this diff Show More