diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/__init__.py b/src/mjlab/asset_zoo/robots/unitree_h1/__init__.py new file mode 100644 index 000000000..14fa90fd1 --- /dev/null +++ b/src/mjlab/asset_zoo/robots/unitree_h1/__init__.py @@ -0,0 +1 @@ +"""Unitree H1 quadruped.""" diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/h1_constants.py b/src/mjlab/asset_zoo/robots/unitree_h1/h1_constants.py new file mode 100644 index 000000000..e99005055 --- /dev/null +++ b/src/mjlab/asset_zoo/robots/unitree_h1/h1_constants.py @@ -0,0 +1,218 @@ +"""Unitree Go1 constants.""" + +from pathlib import Path + +import mujoco + +from mjlab import MJLAB_SRC_PATH +from mjlab.entities.robots.robot_config import RobotCfg +from mjlab.utils.os import update_assets +from mjlab.utils.spec_editor import ActuatorCfg, CollisionCfg + +## +# MJCF and assets. +## + +H1_XML: Path = ( + MJLAB_SRC_PATH / "asset_zoo" / "robots" / "unitree_h1" / "xmls" / "h1.xml" +) +assert H1_XML.exists() + + +def get_assets(meshdir: str) -> dict[str, bytes]: + assets: dict[str, bytes] = {} + update_assets(assets, H1_XML.parent / "assets", meshdir) + return assets + + +def get_spec() -> mujoco.MjSpec: + spec = mujoco.MjSpec.from_file(str(H1_XML)) + spec.assets = get_assets(spec.meshdir) + return spec + + +## +# Actuator config. +## + +# Rotor inertia. +# Ref: https://github.com/unitreerobotics/unitree_ros/blob/master/robots/h1_description/urdf/h1.urdf#L515 +# Extracted Ixx (rotation along x-axis). +ROTOR_INERTIA = 0.000111842 + +# Gearbox. +# HIP_GEAR_RATIO = 6 +# KNEE_GEAR_RATIO = HIP_GEAR_RATIO * 1.5 + +# HIP_ACTUATOR = ElectricActuator( +# reflected_inertia=reflected_inertia(ROTOR_INERTIA, HIP_GEAR_RATIO), +# velocity_limit=30.1, +# effort_limit=23.7, +# ) +# KNEE_ACTUATOR = ElectricActuator( +# reflected_inertia=reflected_inertia(ROTOR_INERTIA, KNEE_GEAR_RATIO), +# velocity_limit=20.06, +# effort_limit=35.55, +# ) + +# H1_LEGS_ACTUATOR_CFG = ActuatorCfg( +# joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee", "torso"], +# effort_limit=300, +# stiffness=150.0, +# # stiffness={ +# # ".*_hip_yaw": 150.0, +# # ".*_hip_roll": 150.0, +# # ".*_hip_pitch": 200.0, +# # ".*_knee": 200.0, +# # "torso": 200.0, +# # }, +# damping=5.0, +# # damping={ +# # ".*_hip_yaw": 5.0, +# # ".*_hip_roll": 5.0, +# # ".*_hip_pitch": 5.0, +# # ".*_knee": 5.0, +# # "torso": 5.0, +# # }, +# ) +# H1_FEET_ACTUATOR_CFG = ActuatorCfg( +# joint_names_expr=[".*_ankle"], +# effort_limit=100, +# stiffness=20.0, #{".*_ankle": 20.0}, +# damping=4.0, #{".*_ankle": 4.0}, +# ) + +# H1_ARMS_ACTUATOR_CFG = ActuatorCfg( +# joint_names_expr=[".*_shoulder_pitch", ".*_shoulder_roll", ".*_shoulder_yaw", ".*_elbow"], +# effort_limit=300, +# stiffness=40.0, +# damping=10.0, +# # stiffness={ +# # ".*_shoulder_pitch": 40.0, +# # ".*_shoulder_roll": 40.0, +# # ".*_shoulder_yaw": 40.0, +# # ".*_elbow": 40.0, +# # }, +# # damping={ +# # ".*_shoulder_pitch": 10.0, +# # ".*_shoulder_roll": 10.0, +# # ".*_shoulder_yaw": 10.0, +# # ".*_elbow": 10.0, +# # }, +# ) +# ## +# # Keyframes. +# ## + + +# INIT_STATE = RobotCfg.InitialStateCfg( +# pos=(0.0, 0.0, 1.05), +# joint_pos={ +# ".*_hip_yaw": 0.0, +# ".*_hip_roll": 0.0, +# ".*_hip_pitch": -0.28, # -16 degrees +# ".*_knee": 0.79, # 45 degrees +# ".*_ankle": -0.52, # -30 degrees +# "torso": 0.0, +# ".*_shoulder_pitch": 0.28, +# ".*_shoulder_roll": 0.0, +# ".*_shoulder_yaw": 0.0, +# ".*_elbow": 0.52, +# }, +# ) + + +H1_LEGS_ACTUATOR_CFG = ActuatorCfg( + joint_names_expr=[ + ".*_hip_yaw$", + ".*_hip_roll$", + ".*_hip_pitch$", + ".*_knee_joint$", # was .*_knee + "torso$", # was torso + ], + effort_limit=300, + stiffness=150.0, + damping=5.0, +) + +H1_FEET_ACTUATOR_CFG = ActuatorCfg( + joint_names_expr=[".*_ankle$"], + effort_limit=100, + stiffness=20.0, + damping=4.0, +) + +H1_ARMS_ACTUATOR_CFG = ActuatorCfg( + joint_names_expr=[ + ".*_shoulder_pitch$", + ".*_shoulder_roll$", + ".*_shoulder_yaw$", + ".*_elbow$", + ], + effort_limit=300, + stiffness=40.0, + damping=10.0, +) + +INIT_STATE = RobotCfg.InitialStateCfg( + pos=(0.0, 0.0, 1.05), + joint_pos={ + ".*_hip_yaw$": 0.0, + ".*_hip_roll$": 0.0, + ".*_hip_pitch$": -0.28, + ".*_knee_joint$": 0.79, # was .*_knee + ".*_ankle$": -0.52, + "torso$": 0.0, # was torso + ".*_shoulder_pitch$": 0.28, + ".*_shoulder_roll$": 0.0, + ".*_shoulder_yaw$": 0.0, + ".*_elbow$": 0.52, + }, +) + + +## +# Collision config. +## + +_foot_regex = "^[right][left]_foot_collision$" + +# This disables all collisions except the feet. +# Furthermore, feet self collisions are disabled. +FEET_ONLY_COLLISION = CollisionCfg( + geom_names_expr=[_foot_regex], + contype=0, + conaffinity=1, + condim=3, + priority=1, + friction=(0.6,), + solimp=(0.9, 0.95, 0.023), +) + +# This enables all collisions, excluding self collisions. +# Foot collisions are given custom condim, friction and solimp. +FULL_COLLISION = CollisionCfg( + geom_names_expr=[".*_collision"], + condim={_foot_regex: 3}, + priority={_foot_regex: 1}, + friction={_foot_regex: (0.6,)}, + solimp={_foot_regex: (0.9, 0.95, 0.023)}, + contype=1, + conaffinity=0, +) + +## +# Final config. +## + +H1_ROBOT_CFG = RobotCfg( + init_state=INIT_STATE, + actuators=( + H1_LEGS_ACTUATOR_CFG, + H1_FEET_ACTUATOR_CFG, + H1_ARMS_ACTUATOR_CFG, + ), + soft_joint_pos_limit_factor=0.9, + collisions=(FULL_COLLISION,), + spec_fn=get_spec, +) diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_ankle_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_ankle_link.stl new file mode 100644 index 000000000..2fb686914 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_ankle_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_elbow_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_elbow_link.stl new file mode 100644 index 000000000..5f798ca07 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_elbow_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_pitch_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_pitch_link.stl new file mode 100644 index 000000000..e5898ab49 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_pitch_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_roll_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_roll_link.stl new file mode 100644 index 000000000..5ade02bc0 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_roll_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_yaw_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_yaw_link.stl new file mode 100644 index 000000000..3bcc4b873 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_hip_yaw_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_knee_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_knee_link.stl new file mode 100644 index 000000000..18174eed9 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_knee_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_pitch_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_pitch_link.stl new file mode 100644 index 000000000..be81370b2 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_pitch_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_roll_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_roll_link.stl new file mode 100644 index 000000000..a59bb640f Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_roll_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_yaw_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_yaw_link.stl new file mode 100644 index 000000000..01d3c75b2 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/left_shoulder_yaw_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/logo_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/logo_link.stl new file mode 100644 index 000000000..c396d51d8 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/logo_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/pelvis.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/pelvis.stl new file mode 100644 index 000000000..05e5512c7 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/pelvis.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_ankle_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_ankle_link.stl new file mode 100644 index 000000000..5c85b2b07 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_ankle_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_elbow_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_elbow_link.stl new file mode 100644 index 000000000..f4c03e3af Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_elbow_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_pitch_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_pitch_link.stl new file mode 100644 index 000000000..1d4e515c1 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_pitch_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_roll_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_roll_link.stl new file mode 100644 index 000000000..d2a0af9bb Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_roll_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_yaw_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_yaw_link.stl new file mode 100644 index 000000000..6c8ffd59e Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_hip_yaw_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_knee_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_knee_link.stl new file mode 100644 index 000000000..1ed90cc62 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_knee_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_pitch_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_pitch_link.stl new file mode 100644 index 000000000..f77ab2b8b Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_pitch_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_roll_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_roll_link.stl new file mode 100644 index 000000000..a98398f9e Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_roll_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_yaw_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_yaw_link.stl new file mode 100644 index 000000000..7943bab36 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/right_shoulder_yaw_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/torso_link.stl b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/torso_link.stl new file mode 100644 index 000000000..335b2f191 Binary files /dev/null and b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/assets/torso_link.stl differ diff --git a/src/mjlab/asset_zoo/robots/unitree_h1/xmls/h1.xml b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/h1.xml new file mode 100644 index 000000000..ecdb6a345 --- /dev/null +++ b/src/mjlab/asset_zoo/robots/unitree_h1/xmls/h1.xml @@ -0,0 +1,242 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/mjlab/tasks/locomotion/velocity/config/g1/__init__.py b/src/mjlab/tasks/locomotion/velocity/config/g1/__init__.py new file mode 100644 index 000000000..ab309cd3e --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/g1/__init__.py @@ -0,0 +1,11 @@ +import gymnasium as gym + +gym.register( + id="Mjlab-Velocity-Flat-Unitree-G1-v0", + entry_point="mjlab.envs:ManagerBasedRlEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.flat_env_cfg:UnitreeG1FlatEnvCfg", + "rl_cfg_entry_point": f"{__name__}.rl_cfg:UnitreeG1FlatPPORunnerCfg", + }, +) diff --git a/src/mjlab/tasks/locomotion/velocity/config/g1/flat_env_cfg.py b/src/mjlab/tasks/locomotion/velocity/config/g1/flat_env_cfg.py new file mode 100644 index 000000000..f7073806a --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/g1/flat_env_cfg.py @@ -0,0 +1,30 @@ +from dataclasses import dataclass, replace + +from mjlab.asset_zoo.robots.unitree_g1.g1_constants import G1_ROBOT_CFG +from mjlab.sensors import ContactSensorCfg +from mjlab.tasks.locomotion.velocity.velocity_env_cfg import ( + LocomotionVelocityFlatEnvCfg, +) + + +@dataclass +class UnitreeG1FlatEnvCfg(LocomotionVelocityFlatEnvCfg): + def __post_init__(self): + super().__post_init__() + + g1_cfg = replace(G1_ROBOT_CFG) + g1_cfg.joint_pos_weight = {".*knee_joint": 0.1} + self.scene.robots = {"robot": g1_cfg} + self.events.push_robot = None + self.observations.policy.enable_corruption = False + self.scene.sensors = { + "feet_contact_forces": ContactSensorCfg( + entity_name="robot", + history_length=3, + track_air_time=True, + filter_expr=[".*knee.*"], + geom_filter_expr=[".*_foot3_collision"], + ), + } + self.sim.njmax = 300 + self.sim.nconmax = 100000 diff --git a/src/mjlab/tasks/locomotion/velocity/config/g1/rl_cfg.py b/src/mjlab/tasks/locomotion/velocity/config/g1/rl_cfg.py new file mode 100644 index 000000000..048425c72 --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/g1/rl_cfg.py @@ -0,0 +1,43 @@ +from dataclasses import dataclass, field + +from mjlab.rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoAlgorithmCfg, +) + + +@dataclass +class UnitreeG1FlatPPORunnerCfg(RslRlOnPolicyRunnerCfg): + policy: RslRlPpoActorCriticCfg = field( + default_factory=lambda: RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_obs_normalization=False, + critic_obs_normalization=False, + actor_hidden_dims=(512, 256, 128), + critic_hidden_dims=(512, 256, 128), + activation="elu", + ) + ) + algorithm: RslRlPpoAlgorithmCfg = field( + default_factory=lambda: RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.01, + num_learning_epochs=5, + num_mini_batches=4, + learning_rate=1.0e-3, + schedule="adaptive", + gamma=0.99, + lam=0.95, + desired_kl=0.01, + max_grad_norm=1.0, + ) + ) + + def __post_init__(self) -> None: + self.num_steps_per_env = 24 + self.max_iterations = 1500 + self.save_interval = 50 + self.experiment_name = "G1_flat" diff --git a/src/mjlab/tasks/locomotion/velocity/config/h1/__init__.py b/src/mjlab/tasks/locomotion/velocity/config/h1/__init__.py new file mode 100644 index 000000000..649e00546 --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/h1/__init__.py @@ -0,0 +1,11 @@ +import gymnasium as gym + +gym.register( + id="Mjlab-Velocity-Flat-Unitree-H1-v0", + entry_point="mjlab.envs:ManagerBasedRlEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.flat_env_cfg:UnitreeH1FlatEnvCfg", + "rl_cfg_entry_point": f"{__name__}.rl_cfg:UnitreeH1FlatPPORunnerCfg", + }, +) diff --git a/src/mjlab/tasks/locomotion/velocity/config/h1/flat_env_cfg.py b/src/mjlab/tasks/locomotion/velocity/config/h1/flat_env_cfg.py new file mode 100644 index 000000000..8d516c28b --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/h1/flat_env_cfg.py @@ -0,0 +1,28 @@ +from dataclasses import dataclass, replace + +from mjlab.asset_zoo.robots.unitree_h1.h1_constants import H1_ROBOT_CFG +from mjlab.sensors import ContactSensorCfg +from mjlab.tasks.locomotion.velocity.velocity_env_cfg import ( + LocomotionVelocityFlatEnvCfg, +) + + +@dataclass +class UnitreeH1FlatEnvCfg(LocomotionVelocityFlatEnvCfg): + def __post_init__(self): + super().__post_init__() + + h1_cfg = replace(H1_ROBOT_CFG) + h1_cfg.joint_pos_weight = {".*knee_joint": 0.1} + self.scene.robots = {"robot": h1_cfg} + self.events.push_robot = None + self.observations.policy.enable_corruption = False + self.scene.sensors = { + "feet_contact_forces": ContactSensorCfg( + entity_name="robot", + history_length=3, + track_air_time=True, + filter_expr=[".*knee.*"], + geom_filter_expr=[".*ankle_collision"], + ), + } diff --git a/src/mjlab/tasks/locomotion/velocity/config/h1/rl_cfg.py b/src/mjlab/tasks/locomotion/velocity/config/h1/rl_cfg.py new file mode 100644 index 000000000..15758af49 --- /dev/null +++ b/src/mjlab/tasks/locomotion/velocity/config/h1/rl_cfg.py @@ -0,0 +1,43 @@ +from dataclasses import dataclass, field + +from mjlab.rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoAlgorithmCfg, +) + + +@dataclass +class UnitreeH1FlatPPORunnerCfg(RslRlOnPolicyRunnerCfg): + policy: RslRlPpoActorCriticCfg = field( + default_factory=lambda: RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_obs_normalization=False, + critic_obs_normalization=False, + actor_hidden_dims=(512, 256, 128), + critic_hidden_dims=(512, 256, 128), + activation="elu", + ) + ) + algorithm: RslRlPpoAlgorithmCfg = field( + default_factory=lambda: RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.01, + num_learning_epochs=5, + num_mini_batches=4, + learning_rate=1.0e-3, + schedule="adaptive", + gamma=0.99, + lam=0.95, + desired_kl=0.01, + max_grad_norm=1.0, + ) + ) + + def __post_init__(self) -> None: + self.num_steps_per_env = 24 + self.max_iterations = 1500 + self.save_interval = 50 + self.experiment_name = "H1_flat" diff --git a/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py b/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py index 1ba5ac3d7..419eb409e 100644 --- a/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py +++ b/src/mjlab/tasks/locomotion/velocity/velocity_env_cfg.py @@ -270,7 +270,7 @@ def __post_init__(self): self.sim.mujoco.integrator = "implicitfast" self.sim.mujoco.cone = "pyramidal" self.sim.mujoco.timestep = 0.005 - self.sim.num_envs = 1 + self.sim.num_envs = 4096 self.sim.nconmax = 40000 self.sim.njmax = 100 self.sim.mujoco.iterations = 10