Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -35,3 +35,25 @@
"sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Unitree-A1-Warp-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeA1RoughEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeA1RoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Unitree-A1-Warp-Play-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeA1RoughEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeA1RoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)
Original file line number Diff line number Diff line change
Expand Up @@ -10,25 +10,20 @@

from .rough_env_cfg import UnitreeA1RoughEnvCfg

# Mirror of stable Unitree A1 ``PhysicsCfg.newton``. Inlined to avoid importing
# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``).
_FLAT_NEWTON_CFG = NewtonCfg(
solver_cfg=MJWarpSolverCfg(njmax=60, nconmax=30, cone="pyramidal", impratio=1, integrator="implicitfast"),
num_substeps=1,
debug_mode=False,
)


@configclass
class UnitreeA1FlatEnvCfg(UnitreeA1RoughEnvCfg):
sim: SimulationCfg = SimulationCfg(
physics=NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=60,
nconmax=30,
cone="pyramidal",
impratio=1,
integrator="implicitfast",
),
num_substeps=1,
debug_mode=False,
)
)
sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG)

def __post_init__(self):
# post init of parent
super().__post_init__()

# override rewards
Expand All @@ -38,16 +33,12 @@ def __post_init__(self):
# change terrain to flat
self.scene.terrain.terrain_type = "plane"
self.scene.terrain.terrain_generator = None
# no height scan
# self.scene.height_scanner = None
# self.observations.policy.height_scan = None
# no terrain curriculum
self.curriculum.terrain_levels = None


class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg):
def __post_init__(self) -> None:
# post init of parent
super().__post_init__()

# make a smaller scene for play
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,3 +35,31 @@
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-B-Warp-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalBRoughEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerCfg",
"rsl_rl_with_symmetry_cfg_entry_point": (
f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerWithSymmetryCfg"
),
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-B-Warp-Play-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalBRoughEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerCfg",
"rsl_rl_with_symmetry_cfg_entry_point": (
f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerWithSymmetryCfg"
),
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)
Original file line number Diff line number Diff line change
Expand Up @@ -10,25 +10,20 @@

from .rough_env_cfg import AnymalBRoughEnvCfg

# Mirror of stable Anymal-B ``PhysicsCfg.newton``. Inlined to avoid importing
# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``).
_FLAT_NEWTON_CFG = NewtonCfg(
solver_cfg=MJWarpSolverCfg(njmax=75, nconmax=15, cone="elliptic", impratio=100, integrator="implicitfast"),
num_substeps=1,
debug_mode=False,
)


@configclass
class AnymalBFlatEnvCfg(AnymalBRoughEnvCfg):
sim: SimulationCfg = SimulationCfg(
physics=NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=75,
nconmax=15,
cone="elliptic",
impratio=100,
integrator="implicitfast",
),
num_substeps=1,
debug_mode=False,
)
)
sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG)

def __post_init__(self):
# post init of parent
super().__post_init__()

# override rewards
Expand All @@ -38,16 +33,12 @@ def __post_init__(self):
# change terrain to flat
self.scene.terrain.terrain_type = "plane"
self.scene.terrain.terrain_generator = None
# no height scan
self.scene.height_scanner = None
self.observations.policy.height_scan = None
# no terrain curriculum
self.curriculum.terrain_levels = None


class AnymalBFlatEnvCfg_PLAY(AnymalBFlatEnvCfg):
def __post_init__(self) -> None:
# post init of parent
super().__post_init__()

# make a smaller scene for play
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,20 +15,26 @@ class AnymalBRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
def __post_init__(self):
super().__post_init__()
self.scene.robot = ANYMAL_B_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
self.manager_call_max_mode = {"Scene": 1}


@configclass
class AnymalBRoughEnvCfg_PLAY(AnymalBRoughEnvCfg):
def __post_init__(self):
super().__post_init__()

# make a smaller scene for play
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
# spawn the robot randomly in the grid (instead of their terrain levels)
self.scene.terrain.max_init_terrain_level = None
# reduce the number of terrains to save memory
if self.scene.terrain.terrain_generator is not None:
self.scene.terrain.terrain_generator.num_rows = 5
self.scene.terrain.terrain_generator.num_cols = 5
self.scene.terrain.terrain_generator.curriculum = False

# disable randomization for play
self.observations.policy.enable_corruption = False
# remove random pushing event
self.events.base_external_force_torque = None
self.events.push_robot = None
Original file line number Diff line number Diff line change
Expand Up @@ -37,3 +37,33 @@
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-C-Warp-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalCRoughEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerCfg",
"rsl_rl_with_symmetry_cfg_entry_point": (
f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerWithSymmetryCfg"
),
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-C-Warp-Play-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalCRoughEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerCfg",
"rsl_rl_with_symmetry_cfg_entry_point": (
f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerWithSymmetryCfg"
),
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)
Original file line number Diff line number Diff line change
Expand Up @@ -10,25 +10,20 @@

from .rough_env_cfg import AnymalCRoughEnvCfg

# Mirror of stable Anymal-C ``PhysicsCfg.newton``. Inlined to avoid importing
# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``).
_FLAT_NEWTON_CFG = NewtonCfg(
solver_cfg=MJWarpSolverCfg(njmax=120, nconmax=15, cone="elliptic", impratio=100, integrator="implicitfast"),
num_substeps=1,
debug_mode=False,
)


@configclass
class AnymalCFlatEnvCfg(AnymalCRoughEnvCfg):
sim: SimulationCfg = SimulationCfg(
physics=NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=120,
nconmax=15,
cone="elliptic",
impratio=100,
integrator="implicitfast",
),
num_substeps=1,
debug_mode=False,
)
)
sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG)

def __post_init__(self):
# post init of parent
super().__post_init__()

# override rewards
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ def __post_init__(self):
# switch robot to anymal-c
self.scene.robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
self.scene.robot.actuators["legs"].armature = 0.01
self.manager_call_max_mode = {"Scene": 1}


@configclass
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,31 +12,6 @@
# Register Gym environments.
##

# Rough env disabled: requires isaaclab_physx which is not yet available on dev/newton.
# The package exists on upstream/develop (commit 308400f1d35) but has not been merged.
# Re-enable once dev/newton picks up isaaclab_physx.
# gym.register(
# id="Isaac-Velocity-Rough-Anymal-D-Warp-v0",
# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
# disable_env_checker=True,
# kwargs={
# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg",
# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
# },
# )

# gym.register(
# id="Isaac-Velocity-Rough-Anymal-D-Warp-Play-v0",
# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
# disable_env_checker=True,
# kwargs={
# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY",
# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
# },
# )

gym.register(
id="Isaac-Velocity-Flat-Anymal-D-Warp-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
Expand All @@ -58,3 +33,25 @@
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-D-Warp-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Velocity-Rough-Anymal-D-Warp-Play-v0",
entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)
Original file line number Diff line number Diff line change
Expand Up @@ -10,37 +10,43 @@

from .rough_env_cfg import AnymalDRoughEnvCfg

# Mirror of stable AnymalD ``PhysicsCfg.newton``. Inlined to avoid importing the
# stable ``PhysicsCfg`` (which would chain into ``isaaclab_physx`` and ``pxr`` at
# module-load time, before SimulationApp has initialised the Kit extensions).
_FLAT_NEWTON_CFG = NewtonCfg(
solver_cfg=MJWarpSolverCfg(njmax=60, nconmax=25, cone="elliptic", impratio=100.0),
num_substeps=1,
debug_mode=False,
)


@configclass
class AnymalDFlatEnvCfg(AnymalDRoughEnvCfg):
sim: SimulationCfg = SimulationCfg(
physics=NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=60,
nconmax=25,
cone="elliptic",
impratio=100.0,
),
num_substeps=1,
debug_mode=False,
)
)
sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG)

def __post_init__(self):
super().__post_init__()

# override rewards
self.rewards.flat_orientation_l2.weight = -5.0
self.rewards.dof_torques_l2.weight = -2.5e-5
self.rewards.feet_air_time.weight = 0.5
# change terrain to flat
self.scene.terrain.terrain_type = "plane"
self.scene.terrain.terrain_generator = None
# no terrain curriculum
self.curriculum.terrain_levels = None


class AnymalDFlatEnvCfg_PLAY(AnymalDFlatEnvCfg):
def __post_init__(self) -> None:
super().__post_init__()

# make a smaller scene for play
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
# disable randomization for play
self.observations.policy.enable_corruption = False
# remove random pushing event
self.events.base_external_force_torque = None
self.events.push_robot = None
Loading
Loading