diff --git a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/g1/29dof/velocity_env_cfg.py b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/g1/29dof/velocity_env_cfg.py index ea9b65ba..bca94441 100644 --- a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/g1/29dof/velocity_env_cfg.py +++ b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/g1/29dof/velocity_env_cfg.py @@ -401,6 +401,7 @@ class RobotPlayEnvCfg(RobotEnvCfg): def __post_init__(self): super().__post_init__() self.scene.num_envs = 32 - self.scene.terrain.terrain_generator.num_rows = 2 - self.scene.terrain.terrain_generator.num_cols = 10 + if self.scene.terrain.terrain_generator is not None: + self.scene.terrain.terrain_generator.num_rows = 2 + self.scene.terrain.terrain_generator.num_cols = 10 self.commands.base_velocity.ranges = self.commands.base_velocity.limit_ranges diff --git a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/go2/velocity_env_cfg.py b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/go2/velocity_env_cfg.py index 7496d767..67295879 100644 --- a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/go2/velocity_env_cfg.py +++ b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/go2/velocity_env_cfg.py @@ -410,6 +410,7 @@ class RobotPlayEnvCfg(RobotEnvCfg): def __post_init__(self): super().__post_init__() self.scene.num_envs = 32 - self.scene.terrain.terrain_generator.num_rows = 2 - self.scene.terrain.terrain_generator.num_cols = 1 + if self.scene.terrain.terrain_generator is not None: + self.scene.terrain.terrain_generator.num_rows = 2 + self.scene.terrain.terrain_generator.num_cols = 1 self.commands.base_velocity.ranges = self.commands.base_velocity.limit_ranges diff --git a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/h1/velocity_env_cfg.py b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/h1/velocity_env_cfg.py index 9241aa41..1df969e2 100644 --- a/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/h1/velocity_env_cfg.py +++ b/source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/robots/h1/velocity_env_cfg.py @@ -415,6 +415,7 @@ class RobotPlayEnvCfg(RobotEnvCfg): def __post_init__(self): super().__post_init__() self.scene.num_envs = 32 - self.scene.terrain.terrain_generator.num_rows = 2 - self.scene.terrain.terrain_generator.num_cols = 10 + if self.scene.terrain.terrain_generator is not None: + self.scene.terrain.terrain_generator.num_rows = 2 + self.scene.terrain.terrain_generator.num_cols = 10 self.commands.base_velocity.ranges = self.commands.base_velocity.limit_ranges