Skip to content

Commit

Permalink
Address MR comments
Browse files Browse the repository at this point in the history
  • Loading branch information
lgulich committed Feb 18, 2025
1 parent a247957 commit 3159e03
Show file tree
Hide file tree
Showing 13 changed files with 176 additions and 236 deletions.
71 changes: 29 additions & 42 deletions source/isaaclab_assets/isaaclab_assets/robots/agility.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,50 +3,37 @@
#
# SPDX-License-Identifier: BSD-3-Clause

import pathlib
from typing import Literal

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

FILE_DIR = pathlib.Path(__file__).parent


def get_digit_articulation_cfg(
fixed_base: bool = False,
actuator_type: Literal["explicit", "implicit"] = "implicit",
) -> ArticulationCfg:
"""
Get an articulation config for a Agility Digit robot.
The robot can be made hanging in the air with the parameter `fixed_base`.
"""
if actuator_type == "implicit":
ActuatorCfg = ImplicitActuatorCfg
elif actuator_type == "explicit":
ActuatorCfg = IdealPDActuatorCfg

articulation_cfg = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Agility/Digit/digit_v4.usd",
activate_contact_sensors=True,
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,
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 1.05),
),
soft_joint_pos_limit_factor=0.9,
actuators={
"all": ActuatorCfg(
joint_names_expr=".*",
stiffness=None,
damping=None,
),
},
)

if fixed_base:
articulation_cfg.init_state.pos = (0.0, 0.0, 2.0)
articulation_cfg.spawn.articulation_props.fix_root_link = True

return articulation_cfg
},
)
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-Velocity-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-Velocity-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
Expand Up @@ -5,6 +5,8 @@

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
Expand All @@ -14,8 +16,7 @@

import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
import isaaclab_tasks.manager_based.manipulation.reach.mdp as manipulation_mdp

from .rough_env_cfg import ARM_JOINT_NAMES, LEG_JOINT_NAMES, DigitRewards, DigitRoughEnvCfg
from isaaclab_tasks.manager_based.locomotion.velocity.config.digit.rough_env_cfg import DigitRewards, DigitRoughEnvCfg


@configclass
Expand All @@ -33,7 +34,7 @@ class DigitLocoManipRewards(DigitRewards):
weight=-2.0,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"command_name": "left_ee_position",
"command_name": "left_ee_pose",
},
)

Expand All @@ -42,7 +43,7 @@ class DigitLocoManipRewards(DigitRewards):
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"std": 0.05,
"command_name": "left_ee_position",
"command_name": "left_ee_pose",
},
weight=2.0,
)
Expand All @@ -52,7 +53,7 @@ class DigitLocoManipRewards(DigitRewards):
weight=-0.2,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="left_arm_wrist_yaw"),
"command_name": "left_ee_position",
"command_name": "left_ee_pose",
},
)

Expand All @@ -61,7 +62,7 @@ class DigitLocoManipRewards(DigitRewards):
weight=-2.0,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"command_name": "right_ee_position",
"command_name": "right_ee_pose",
},
)

Expand All @@ -70,7 +71,7 @@ class DigitLocoManipRewards(DigitRewards):
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"std": 0.05,
"command_name": "right_ee_position",
"command_name": "right_ee_pose",
},
weight=2.0,
)
Expand All @@ -80,7 +81,7 @@ class DigitLocoManipRewards(DigitRewards):
weight=-0.2,
params={
"asset_cfg": SceneEntityCfg("robot", body_names="right_arm_wrist_yaw"),
"command_name": "right_ee_position",
"command_name": "right_ee_pose",
},
)

Expand All @@ -90,8 +91,14 @@ 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),)
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),
Expand All @@ -100,13 +107,13 @@ class PolicyCfg(ObsGroup):
func=mdp.generated_commands,
params={"command_name": "base_velocity"},
)
left_ee_pos_command = ObsTerm(
left_ee_pose_command = ObsTerm(
func=mdp.generated_commands,
params={"command_name": "left_ee_position"},
params={"command_name": "left_ee_pose"},
)
right_ee_pos_command = ObsTerm(
right_ee_pose_command = ObsTerm(
func=mdp.generated_commands,
params={"command_name": "right_ee_position"},
params={"command_name": "right_ee_pose"},
)
joint_pos = ObsTerm(
func=mdp.joint_pos_rel,
Expand All @@ -119,12 +126,10 @@ class PolicyCfg(ObsGroup):
noise=Unoise(n_min=-1.5, n_max=1.5),
)
actions = ObsTerm(func=mdp.last_action)
height_scan = ObsTerm(
func=mdp.height_scan,
params={"sensor_cfg": SceneEntityCfg("height_scanner")},
noise=Unoise(n_min=-0.1, n_max=0.1),
clip=(-1.0, 1.0),
)

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

policy = PolicyCfg()

Expand All @@ -146,7 +151,7 @@ class DigitLocoManipCommands:
),
)

left_ee_position = mdp.UniformPoseCommandCfg(
left_ee_pose = mdp.UniformPoseCommandCfg(
asset_name="robot",
body_name="left_arm_wrist_yaw",
resampling_time_range=(1.0, 3.0),
Expand All @@ -155,13 +160,13 @@ class DigitLocoManipCommands:
pos_x=(0.25, 0.45),
pos_y=(0.15, 0.3),
pos_z=(-0.05, 0.15),
roll=(0.0, 0.0),
pitch=(0.0, 0.0),
yaw=(math.pi / 2.0, math.pi / 2.0),
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_position = mdp.UniformPoseCommandCfg(
right_ee_pose = mdp.UniformPoseCommandCfg(
asset_name="robot",
body_name="right_arm_wrist_yaw",
resampling_time_range=(1.0, 3.0),
Expand All @@ -170,9 +175,9 @@ class DigitLocoManipCommands:
pos_x=(0.25, 0.45),
pos_y=(-0.3, -0.15),
pos_z=(-0.05, 0.15),
roll=(0.0, 0.0),
pitch=(0.0, 0.0),
yaw=(-math.pi / 2.0, -math.pi / 2.0),
roll=(-0.1, 0.1),
pitch=(-0.1, 0.1),
yaw=(-math.pi / 2.0 - 0.1, -math.pi / 2.0 + 0.1),
),
)

Expand Down Expand Up @@ -221,7 +226,11 @@ def __post_init__(self) -> None:
self.randomization.base_external_force_torque = None
self.randomization.push_robot = None
self.randomization.reset_base.params = {
"pose_range": {"x": (-0.0, 0.0), "y": (-0.0, 0.0), "yaw": (-3.1415 * 0, 3.1415 * 0),},
"pose_range": {
"x": (-0.0, 0.0),
"y": (-0.0, 0.0),
"yaw": (-3.1415 * 0, 3.1415 * 0),
},
"velocity_range": {
"x": (-0.0, 0.0),
"y": (-0.0, 0.0),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,25 +52,3 @@
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:DigitRoughPPORunnerCfg",
},
)


gym.register(
id="Isaac-Velocity-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-Velocity-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",
},
)
Loading

0 comments on commit 3159e03

Please sign in to comment.