From f645048401ace16054cfa0805ee185a6604e7cfe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Quentin=20Gallou=C3=A9dec?= <45557362+qgallouedec@users.noreply.github.com> Date: Thu, 27 Apr 2023 11:05:19 +0200 Subject: [PATCH] Use render arguments for debug GUI (#64) * Debug visualizer use render arg * update version --- docs/conf.py | 2 +- panda_gym/envs/core.py | 11 ++++++++++- panda_gym/envs/tasks/flip.py | 1 - panda_gym/envs/tasks/pick_and_place.py | 1 - panda_gym/envs/tasks/push.py | 1 - panda_gym/envs/tasks/reach.py | 1 - panda_gym/envs/tasks/slide.py | 1 - panda_gym/envs/tasks/stack.py | 1 - panda_gym/version.txt | 2 +- 9 files changed, 12 insertions(+), 9 deletions(-) diff --git a/docs/conf.py b/docs/conf.py index ade45b68..1d8bc672 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -23,7 +23,7 @@ author = "Quentin Gallouédec" # The full version, including alpha/beta/rc tags -release = "v3.0.5" +release = "v3.0.6" # -- General configuration --------------------------------------------------- diff --git a/panda_gym/envs/core.py b/panda_gym/envs/core.py index 58170903..2004b8cf 100644 --- a/panda_gym/envs/core.py +++ b/panda_gym/envs/core.py @@ -247,11 +247,20 @@ def __init__( self.render_width = render_width self.render_height = render_height - self.render_target_position = render_target_position + self.render_target_position = ( + render_target_position if render_target_position is not None else np.array([0.0, 0.0, 0.0]) + ) self.render_distance = render_distance self.render_yaw = render_yaw self.render_pitch = render_pitch self.render_roll = render_roll + with self.sim.no_rendering(): + self.sim.place_visualizer( + target_position=self.render_target_position, + distance=self.render_distance, + yaw=self.render_yaw, + pitch=self.render_pitch, + ) def _get_obs(self) -> Dict[str, np.ndarray]: robot_obs = self.robot.get_obs().astype(np.float32) # robot state diff --git a/panda_gym/envs/tasks/flip.py b/panda_gym/envs/tasks/flip.py index b3ff5bf5..1df64ceb 100644 --- a/panda_gym/envs/tasks/flip.py +++ b/panda_gym/envs/tasks/flip.py @@ -24,7 +24,6 @@ def __init__( self.obj_range_high = np.array([obj_xy_range / 2, obj_xy_range / 2, 0]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: """Create the scene.""" diff --git a/panda_gym/envs/tasks/pick_and_place.py b/panda_gym/envs/tasks/pick_and_place.py index a71c02e7..47ef2c31 100644 --- a/panda_gym/envs/tasks/pick_and_place.py +++ b/panda_gym/envs/tasks/pick_and_place.py @@ -27,7 +27,6 @@ def __init__( self.obj_range_high = np.array([obj_xy_range / 2, obj_xy_range / 2, 0]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: """Create the scene.""" diff --git a/panda_gym/envs/tasks/push.py b/panda_gym/envs/tasks/push.py index 24721fd7..364fd9d2 100644 --- a/panda_gym/envs/tasks/push.py +++ b/panda_gym/envs/tasks/push.py @@ -25,7 +25,6 @@ def __init__( self.obj_range_high = np.array([obj_xy_range / 2, obj_xy_range / 2, 0]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: self.sim.create_plane(z_offset=-0.4) diff --git a/panda_gym/envs/tasks/reach.py b/panda_gym/envs/tasks/reach.py index e0c279e7..af5a4881 100644 --- a/panda_gym/envs/tasks/reach.py +++ b/panda_gym/envs/tasks/reach.py @@ -23,7 +23,6 @@ def __init__( self.goal_range_high = np.array([goal_range / 2, goal_range / 2, goal_range]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: self.sim.create_plane(z_offset=-0.4) diff --git a/panda_gym/envs/tasks/slide.py b/panda_gym/envs/tasks/slide.py index ad01a97e..04911360 100644 --- a/panda_gym/envs/tasks/slide.py +++ b/panda_gym/envs/tasks/slide.py @@ -26,7 +26,6 @@ def __init__( self.obj_range_high = np.array([obj_xy_range / 2, obj_xy_range / 2, 0]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: self.sim.create_plane(z_offset=-0.4) diff --git a/panda_gym/envs/tasks/stack.py b/panda_gym/envs/tasks/stack.py index af67fd4d..cde63cc1 100644 --- a/panda_gym/envs/tasks/stack.py +++ b/panda_gym/envs/tasks/stack.py @@ -25,7 +25,6 @@ def __init__( self.obj_range_high = np.array([obj_xy_range / 2, obj_xy_range / 2, 0]) with self.sim.no_rendering(): self._create_scene() - self.sim.place_visualizer(target_position=np.zeros(3), distance=0.9, yaw=45, pitch=-30) def _create_scene(self) -> None: self.sim.create_plane(z_offset=-0.4) diff --git a/panda_gym/version.txt b/panda_gym/version.txt index 7da3c168..8ffc1ad6 100644 --- a/panda_gym/version.txt +++ b/panda_gym/version.txt @@ -1 +1 @@ -3.0.5 \ No newline at end of file +3.0.6 \ No newline at end of file