Skip to content

Commit

Permalink
Better seed (#97)
Browse files Browse the repository at this point in the history
* better seed

* numpy dep

---------

Co-authored-by: Quentin Gallouédec <[email protected]>
  • Loading branch information
qgallouedec and qgallouedec authored Jul 4, 2024
1 parent 746ee4d commit 10c4d8a
Show file tree
Hide file tree
Showing 6 changed files with 18 additions and 9 deletions.
2 changes: 1 addition & 1 deletion panda_gym/envs/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ def reset(
self, seed: Optional[int] = None, options: Optional[dict] = None
) -> Tuple[Dict[str, np.ndarray], Dict[str, Any]]:
super().reset(seed=seed, options=options)
self.task.np_random, seed = seeding.np_random(seed)
self.task.np_random = self.np_random
with self.sim.no_rendering():
self.robot.reset()
self.task.reset()
Expand Down
2 changes: 1 addition & 1 deletion panda_gym/envs/tasks/flip.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def reset(self) -> None:

def _sample_goal(self) -> np.ndarray:
"""Randomize goal."""
goal = R.random().as_quat()
goal = R.random(random_state=self.np_random).as_quat()
return goal

def _sample_object(self) -> Tuple[np.ndarray, np.ndarray]:
Expand Down
4 changes: 3 additions & 1 deletion panda_gym/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@ def distance(a: np.ndarray, b: np.ndarray) -> np.ndarray:
np.ndarray: The distance between the arrays.
"""
assert a.shape == b.shape
return np.linalg.norm(a - b, axis=-1)
dist = np.linalg.norm(a - b, axis=-1)
# round at 1e-6 (ensure determinism and avoid numerical noise)
return np.round(dist, 6)


def angle_distance(a: np.ndarray, b: np.ndarray) -> np.ndarray:
Expand Down
2 changes: 1 addition & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
include_package_data=True,
package_data={"panda_gym": ["version.txt"]},
version=__version__,
install_requires=["gymnasium>=0.26", "pybullet", "numpy", "scipy"],
install_requires=["gymnasium>=0.26", "pybullet", "numpy<2", "scipy"],
extras_require={
"develop": ["pytest-cov", "black", "isort", "pytype", "sphinx", "sphinx-rtd-theme"],
},
Expand Down
7 changes: 7 additions & 0 deletions test/envs_test.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import gymnasium as gym
import pytest
from gymnasium.utils.env_checker import check_env

import panda_gym

Expand All @@ -22,3 +23,9 @@ def test_env(env_id):
"""Tests running panda gym envs."""
env = gym.make(env_id)
run_env(env)


@pytest.mark.parametrize("env_id", panda_gym.ENV_IDS)
def test_check_env(env_id):
"""Check envs with the env checker."""
check_env(gym.make(env_id).unwrapped, skip_render_check=True)
10 changes: 5 additions & 5 deletions test/save_and_restore_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,15 @@ def test_save_and_restore_state():
env = gym.make("PandaReach-v3")
env.reset()

state_id = env.save_state()
state_id = env.unwrapped.save_state()

# Perform the action
action = env.action_space.sample()
observation1, _, _, _, _ = env.step(action)

# Restore and perform the same action
env.reset()
env.restore_state(state_id)
env.unwrapped.restore_state(state_id)
observation2, _, _, _, _ = env.step(action)

# The observations in both cases should be equals
Expand All @@ -30,7 +30,7 @@ def test_save_and_restore_state():
def test_remove_state():
env = gym.make("PandaReach-v3")
env.reset()
state_id = env.save_state()
env.remove_state(state_id)
state_id = env.unwrapped.save_state()
env.unwrapped.remove_state(state_id)
with pytest.raises(pybullet.error):
env.restore_state(state_id)
env.unwrapped.restore_state(state_id)

0 comments on commit 10c4d8a

Please sign in to comment.