Skip to content

Commit 2c09429

Browse files
committed
Introduce new feature that allow hydra group override through command line
1 parent 91ad494 commit 2c09429

File tree

6 files changed

+330
-7
lines changed

6 files changed

+330
-7
lines changed

source/isaaclab_tasks/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.10.34"
4+
version = "0.11.0"
55

66
# Description
77
title = "Isaac Lab Environments"

source/isaaclab_tasks/docs/CHANGELOG.rst

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,15 @@
11
Changelog
22
---------
33

4+
0.11.0 (2025-06-18)
5+
~~~~~~~~~~~~~~~~~~~~
6+
7+
Changed
8+
^^^^^^^
9+
10+
* Add new feature that support hydra group config override, and provide example at Isaac-Reach-Franka-v0 env
11+
12+
413
0.10.34 (2025-06-16)
514
~~~~~~~~~~~~~~~~~~~~
615

source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/franka/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
2525
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:FrankaReachPPORunnerCfg",
2626
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml",
27+
"configurable_entry_point": f"{agents.__name__}.configurables:AgentConfigurables",
2728
},
2829
)
2930

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
7+
# All rights reserved.
8+
#
9+
# SPDX-License-Identifier: BSD-3-Clause
10+
11+
12+
from isaaclab.utils import configclass
13+
14+
from isaaclab_rl.rsl_rl import RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg
15+
16+
from ..configurables import EnvConfigurables
17+
18+
19+
@configclass
20+
class AgentConfigurables(EnvConfigurables):
21+
agent: dict[str, any] = {
22+
"policy": {
23+
"large_network": RslRlPpoActorCriticCfg(
24+
init_noise_std=1.0,
25+
actor_hidden_dims=[512, 256, 128, 64],
26+
critic_hidden_dims=[512, 256, 128, 64],
27+
activation="elu",
28+
),
29+
"medium_network": RslRlPpoActorCriticCfg(
30+
init_noise_std=1.0,
31+
actor_hidden_dims=[256, 128, 64],
32+
critic_hidden_dims=[256, 128, 64],
33+
activation="elu",
34+
),
35+
"small_network": RslRlPpoActorCriticCfg(
36+
init_noise_std=1.0,
37+
actor_hidden_dims=[128, 64],
38+
critic_hidden_dims=[128, 64],
39+
activation="elu",
40+
),
41+
},
42+
"algorithm": {
43+
"standard": RslRlPpoAlgorithmCfg(
44+
value_loss_coef=1.0,
45+
use_clipped_value_loss=True,
46+
clip_param=0.2,
47+
entropy_coef=0.001,
48+
num_learning_epochs=8,
49+
num_mini_batches=4,
50+
learning_rate=1.0e-3,
51+
schedule="adaptive",
52+
gamma=0.99,
53+
lam=0.95,
54+
desired_kl=0.01,
55+
max_grad_norm=1.0,
56+
),
57+
"small_batch": RslRlPpoAlgorithmCfg(
58+
value_loss_coef=1.0,
59+
use_clipped_value_loss=True,
60+
clip_param=0.2,
61+
entropy_coef=0.001,
62+
num_learning_epochs=8,
63+
num_mini_batches=16,
64+
learning_rate=1.0e-4,
65+
schedule="adaptive",
66+
gamma=0.99,
67+
lam=0.95,
68+
desired_kl=0.01,
69+
max_grad_norm=1.0,
70+
),
71+
},
72+
}
Lines changed: 174 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,174 @@
1+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
7+
# All rights reserved.
8+
#
9+
# SPDX-License-Identifier: BSD-3-Clause
10+
11+
from isaaclab.managers import EventTermCfg as EventTerm
12+
from isaaclab.managers import ObservationGroupCfg as ObsGroup
13+
from isaaclab.managers import ObservationTermCfg as ObsTerm
14+
from isaaclab.managers import SceneEntityCfg
15+
from isaaclab.utils import configclass
16+
from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise
17+
18+
import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp
19+
20+
from ...reach_env_cfg import EventCfg
21+
22+
23+
# Observation configurations
24+
@configclass
25+
class StateNoNoiseObservationsCfg:
26+
"""Observation specifications for the MDP."""
27+
28+
@configclass
29+
class PolicyCfg(ObsGroup):
30+
"""Observations for policy group."""
31+
32+
# observation terms (order preserved)
33+
joint_pos = ObsTerm(func=mdp.joint_pos_rel)
34+
joint_vel = ObsTerm(func=mdp.joint_vel_rel)
35+
pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "ee_pose"})
36+
actions = ObsTerm(func=mdp.last_action)
37+
38+
def __post_init__(self):
39+
self.enable_corruption = False
40+
self.concatenate_terms = True
41+
42+
# observation groups
43+
policy: PolicyCfg = PolicyCfg()
44+
45+
46+
@configclass
47+
class StateNoisyObservationsCfg:
48+
"""Observation specifications for the MDP."""
49+
50+
@configclass
51+
class PolicyCfg(ObsGroup):
52+
"""Observations for policy group."""
53+
54+
# observation terms (order preserved)
55+
joint_pos = ObsTerm(func=mdp.joint_pos_rel, noise=Unoise(n_min=-0.1, n_max=0.1))
56+
joint_vel = ObsTerm(func=mdp.joint_vel_rel, noise=Unoise(n_min=-0.1, n_max=0.1))
57+
pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "ee_pose"})
58+
actions = ObsTerm(func=mdp.last_action)
59+
60+
def __post_init__(self):
61+
self.enable_corruption = True
62+
self.concatenate_terms = True
63+
64+
# observation groups
65+
policy: PolicyCfg = PolicyCfg()
66+
67+
68+
@configclass
69+
class JointRandPositionFrictionEventCfg(EventCfg):
70+
71+
reset_robot_joint_friction = EventTerm(
72+
func=mdp.randomize_joint_parameters,
73+
min_step_count_between_reset=720,
74+
mode="reset",
75+
params={
76+
"asset_cfg": SceneEntityCfg("robot", joint_names=".*"),
77+
"friction_distribution_params": (0.9, 1.1),
78+
"operation": "scale",
79+
"distribution": "gaussian",
80+
},
81+
)
82+
83+
84+
@configclass
85+
class JointRandPositionFrictionAmartureEventCfg(JointRandPositionFrictionEventCfg):
86+
"""Configuration for events."""
87+
88+
reset_robot_joint_amature = EventTerm(
89+
func=mdp.randomize_joint_parameters,
90+
min_step_count_between_reset=720,
91+
mode="reset",
92+
params={
93+
"asset_cfg": SceneEntityCfg("robot", joint_names=".*"),
94+
"armature_distribution_params": (0.9, 1.1),
95+
"operation": "scale",
96+
"distribution": "gaussian",
97+
},
98+
)
99+
100+
101+
@configclass
102+
class EnvConfigurables:
103+
env: dict[str, any] = {
104+
"observations": {
105+
"state_obs_no_noise": StateNoNoiseObservationsCfg(),
106+
"state_obs_noisy": StateNoisyObservationsCfg(),
107+
},
108+
"actions.arm_action": {
109+
"ik_abs_arm_action": mdp.DifferentialInverseKinematicsActionCfg(
110+
asset_name="robot",
111+
joint_names=["panda_joint.*"],
112+
body_name="panda_hand",
113+
controller=mdp.DifferentialIKControllerCfg(
114+
command_type="pose", use_relative_mode=False, ik_method="dls"
115+
),
116+
body_offset=mdp.DifferentialInverseKinematicsActionCfg.OffsetCfg(pos=[0.0, 0.0, 0.107]),
117+
),
118+
"ik_rel_arm_action": mdp.DifferentialInverseKinematicsActionCfg(
119+
asset_name="robot",
120+
joint_names=["panda_joint.*"],
121+
body_name="panda_hand",
122+
controller=mdp.DifferentialIKControllerCfg(
123+
command_type="pose", use_relative_mode=True, ik_method="dls"
124+
),
125+
scale=0.5,
126+
body_offset=mdp.DifferentialInverseKinematicsActionCfg.OffsetCfg(pos=[0.0, 0.0, 0.107]),
127+
),
128+
"joint_pos_arm_action": mdp.JointPositionActionCfg(
129+
asset_name="robot", joint_names=["panda_joint.*"], scale=0.5, use_default_offset=True
130+
),
131+
"osc_arm_action": mdp.OperationalSpaceControllerActionCfg(
132+
asset_name="robot",
133+
joint_names=["panda_joint.*"],
134+
body_name="panda_hand",
135+
controller_cfg=mdp.OperationalSpaceControllerCfg(
136+
target_types=["pose_abs"],
137+
impedance_mode="variable_kp",
138+
inertial_dynamics_decoupling=True,
139+
partial_inertial_dynamics_decoupling=False,
140+
gravity_compensation=False,
141+
motion_stiffness_task=100.0,
142+
motion_damping_ratio_task=1.0,
143+
motion_stiffness_limits_task=(50.0, 200.0),
144+
nullspace_control="position",
145+
),
146+
nullspace_joint_pos_target="center",
147+
position_scale=1.0,
148+
orientation_scale=1.0,
149+
stiffness_scale=100.0,
150+
),
151+
},
152+
"events": {
153+
"rand_joint_pos_friction": JointRandPositionFrictionEventCfg(),
154+
"rand_joint_pos_friction_amarture": JointRandPositionFrictionAmartureEventCfg(),
155+
},
156+
"events.reset_robot_joints": {
157+
"aggressive": EventTerm(
158+
func=mdp.reset_joints_by_scale,
159+
mode="reset",
160+
params={
161+
"position_range": (0.0, 2.0),
162+
"velocity_range": (0.0, 1.0),
163+
},
164+
),
165+
"easy": EventTerm(
166+
func=mdp.reset_joints_by_scale,
167+
mode="reset",
168+
params={
169+
"position_range": (0.0, 0.5),
170+
"velocity_range": (0.0, 0.0),
171+
},
172+
),
173+
},
174+
}

0 commit comments

Comments
 (0)