Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add digit locomotion examples #1892

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
39 changes: 39 additions & 0 deletions source/isaaclab_assets/isaaclab_assets/robots/agility.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

import isaaclab.sim as sim_utils
from isaaclab.actuators import ImplicitActuatorCfg
from isaaclab.assets.articulation import ArticulationCfg
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR

LEG_JOINT_NAMES = [
".*_hip_roll",
".*_hip_yaw",
".*_hip_pitch",
".*_knee",
".*_toe_a",
".*_toe_b",
]

ARM_JOINT_NAMES = [".*_arm_.*"]


DIGIT_V4_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Agility/Digit/digit_v4.usd",
activate_contact_sensors=True,
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 1.05),
),
soft_joint_pos_limit_factor=0.9,
actuators={
"all": ImplicitActuatorCfg(
joint_names_expr=".*",
stiffness=None,
damping=None,
),
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Locomotion environments for legged robots."""

from .tracking import * # noqa
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##
gym.register(
id="Isaac-Tracking-LocoManip-Digit-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.loco_manip_env_cfg:DigitLocoManipEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DigitLocoManipPPORunnerCfg",
},
)


gym.register(
id="Isaac-Tracking-LocoManip-Digit-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.loco_manip_env_cfg:DigitLocoManipEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DigitLocoManipPPORunnerCfg",
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg

from isaaclab.utils import configclass


@configclass
class DigitLocoManipPPORunnerCfg(RslRlOnPolicyRunnerCfg):
num_steps_per_env = 24
max_iterations = 2000
save_interval = 50
experiment_name = "digit_loco_manip"
empirical_normalization = False
policy = RslRlPpoActorCriticCfg(
init_noise_std=1.0,
actor_hidden_dims=[256, 128, 128],
critic_hidden_dims=[256, 128, 128],
activation="elu",
)
algorithm = 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,
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,227 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

import math

from isaaclab_assets.robots.agility import ARM_JOINT_NAMES, LEG_JOINT_NAMES

from isaaclab.managers import ObservationGroupCfg as ObsGroup
from isaaclab.managers import ObservationTermCfg as ObsTerm
from isaaclab.managers import RewardTermCfg as RewTerm
from isaaclab.managers import SceneEntityCfg
from isaaclab.utils import configclass
from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise

import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
import isaaclab_tasks.manager_based.manipulation.reach.mdp as manipulation_mdp
from isaaclab_tasks.manager_based.locomotion.velocity.config.digit.rough_env_cfg import DigitRewards, DigitRoughEnvCfg


@configclass
class DigitLocoManipRewards(DigitRewards):
joint_deviation_arms = None

joint_vel_hip_yaw = RewTerm(
func=mdp.joint_vel_l2,
weight=-0.001,
params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_leg_hip_yaw"])},
)

left_ee_pos_tracking = RewTerm(
func=manipulation_mdp.position_command_error,
weight=-2.0,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"command_name": "left_ee_pose",
},
)

left_ee_pos_tracking_fine_grained = RewTerm(
func=manipulation_mdp.position_command_error_tanh,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"std": 0.05,
"command_name": "left_ee_pose",
},
weight=2.0,
)

left_end_effector_orientation_tracking = RewTerm(
func=manipulation_mdp.orientation_command_error,
weight=-0.2,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"command_name": "left_ee_pose",
},
)

right_ee_pos_tracking = RewTerm(
func=manipulation_mdp.position_command_error,
weight=-2.0,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"command_name": "right_ee_pose",
},
)

right_ee_pos_tracking_fine_grained = RewTerm(
func=manipulation_mdp.position_command_error_tanh,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"std": 0.05,
"command_name": "right_ee_pose",
},
weight=2.0,
)

right_end_effector_orientation_tracking = RewTerm(
func=manipulation_mdp.orientation_command_error,
weight=-0.2,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"command_name": "right_ee_pose",
},
)


@configclass
class DigitLocoManipObservations:

@configclass
class PolicyCfg(ObsGroup):
base_lin_vel = ObsTerm(
func=mdp.base_lin_vel,
noise=Unoise(n_min=-0.1, n_max=0.1),
)
base_ang_vel = ObsTerm(
func=mdp.base_ang_vel,
noise=Unoise(n_min=-0.2, n_max=0.2),
)
projected_gravity = ObsTerm(
func=mdp.projected_gravity,
noise=Unoise(n_min=-0.05, n_max=0.05),
)
velocity_commands = ObsTerm(
func=mdp.generated_commands,
params={"command_name": "base_velocity"},
)
left_ee_pose_command = ObsTerm(
func=mdp.generated_commands,
params={"command_name": "left_ee_pose"},
)
right_ee_pose_command = ObsTerm(
func=mdp.generated_commands,
params={"command_name": "right_ee_pose"},
)
joint_pos = ObsTerm(
func=mdp.joint_pos_rel,
params={"asset_cfg": SceneEntityCfg("robot", joint_names=LEG_JOINT_NAMES + ARM_JOINT_NAMES)},
noise=Unoise(n_min=-0.01, n_max=0.01),
)
joint_vel = ObsTerm(
func=mdp.joint_vel_rel,
params={"asset_cfg": SceneEntityCfg("robot", joint_names=LEG_JOINT_NAMES + ARM_JOINT_NAMES)},
noise=Unoise(n_min=-1.5, n_max=1.5),
)
actions = ObsTerm(func=mdp.last_action)

def __post_init__(self):
self.enable_corruption = True
self.concatenate_terms = True

policy = PolicyCfg()


@configclass
class DigitLocoManipCommands:
base_velocity = mdp.UniformVelocityCommandCfg(
asset_name="robot",
resampling_time_range=(10.0, 10.0),
rel_standing_envs=0.25,
rel_heading_envs=1.0,
heading_command=True,
debug_vis=True,
ranges=mdp.UniformVelocityCommandCfg.Ranges(
lin_vel_x=(-1.0, 1.0),
lin_vel_y=(-1.0, 1.0),
ang_vel_z=(-1.0, 1.0),
heading=(-math.pi, math.pi),
),
)

left_ee_pose = mdp.UniformPoseCommandCfg(
asset_name="robot",
body_name="left_arm_wrist_yaw",
resampling_time_range=(1.0, 3.0),
debug_vis=True,
ranges=mdp.UniformPoseCommandCfg.Ranges(
pos_x=(0.25, 0.45),
pos_y=(0.15, 0.3),
pos_z=(-0.05, 0.15),
roll=(-0.1, 0.1),
pitch=(-0.1, 0.1),
yaw=(math.pi / 2.0 - 0.1, math.pi / 2.0 + 0.1),
),
)

right_ee_pose = mdp.UniformPoseCommandCfg(
asset_name="robot",
body_name="right_arm_wrist_yaw",
resampling_time_range=(1.0, 3.0),
debug_vis=True,
ranges=mdp.UniformPoseCommandCfg.Ranges(
pos_x=(0.25, 0.45),
pos_y=(-0.3, -0.15),
pos_z=(-0.05, 0.15),
roll=(-0.1, 0.1),
pitch=(-0.1, 0.1),
yaw=(-math.pi / 2.0 - 0.1, -math.pi / 2.0 + 0.1),
),
)


@configclass
class DigitLocoManipEnvCfg(DigitRoughEnvCfg):
rewards: DigitLocoManipRewards = DigitLocoManipRewards()
observations: DigitLocoManipObservations = DigitLocoManipObservations()
commands: DigitLocoManipCommands = DigitLocoManipCommands()

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

self.episode_length_s = 14.0

# Rewards:
self.rewards.flat_orientation_l2.weight = -10.5
self.rewards.termination_penalty.weight = -100.0

# Commands
self.commands.base_velocity.ranges.lin_vel_x = (0.0, 0.8)
self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)

# Change terrain to flat.
self.scene.terrain.terrain_type = "plane"
self.scene.terrain.terrain_generator = None
# Remove height scanner.
self.scene.height_scanner = None
self.observations.policy.height_scan = None
# Remove terrain curriculum.
self.curriculum.terrain_levels = None


class DigitLocoManipEnvCfg_PLAY(DigitLocoManipEnvCfg):

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.
self.randomization.base_external_force_torque = None
self.randomization.push_robot = None
Loading
Loading