Unverified Commit a1e81ccb authored by yijieg's avatar yijieg Committed by GitHub

Adds assembly tasks from Automate project (#2507)

# Description

This MR adds new tasks for assembly tasks based on AutoMate paper. Tasks
are 100 assemblies for diverse parts.

## Type of change

- New feature (non-breaking change which adds functionality)
- This change requires a documentation update

## Screenshots


![00004](https://github.com/user-attachments/assets/01fe26f4-bfc8-4df3-b99d-db3c01448ed5)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

---------
Signed-off-by: 's avatarKelly Guo <kellyguo123@hotmail.com>
Signed-off-by: 's avatarKelly Guo <kellyg@nvidia.com>
Co-authored-by: 's avatarKelly Guo <kellyg@nvidia.com>
Co-authored-by: 's avatarKelly Guo <kellyguo123@hotmail.com>
parent 4737968a
......@@ -42,6 +42,7 @@ Guidelines for modifications:
* Arjun Bhardwaj
* Ashwin Varghese Kuruttukulam
* Bikram Pandit
* Bingjie Tang
* Brayden Zhang
* Cameron Upright
* Calvin Yu
......@@ -110,6 +111,7 @@ Guidelines for modifications:
* Xavier Nal
* Yang Jin
* Yanzi Zhu
* Yijie Guo
* Yujian Zhang
* Yun Liu
* Zhengyu Zhang
......
......@@ -43,7 +43,8 @@ RUN --mount=type=cache,target=/var/cache/apt \
cmake \
git \
libglib2.0-0 \
ncurses-term && \
ncurses-term \
wget && \
apt -y autoremove && apt clean autoclean && \
rm -rf /var/lib/apt/lists/*
......
......@@ -193,6 +193,52 @@ For example:
.. |factory-gear-link| replace:: `Isaac-Factory-GearMesh-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py>`__
.. |factory-nut-link| replace:: `Isaac-Factory-NutThread-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py>`__
Assembly
~~~~~~~~
Environments based on 100 diverse assembly tasks, each involving the insertion of a plug into a socket. These tasks share a common configuration and differ by th geometry and properties of the parts.
You can switch between tasks by specifying the corresponding asset ID. Available asset IDs include:
'00004', '00007', '00014', '00015', '00016', '00021', '00028', '00030', '00032', '00042', '00062', '00074', '00077', '00078', '00081', '00083', '00103', '00110', '00117', '00133', '00138', '00141', '00143', '00163', '00175', '00186', '00187', '00190', '00192', '00210', '00211', '00213', '00255', '00256', '00271', '00293', '00296', '00301', '00308', '00318', '00319', '00320', '00329', '00340', '00345', '00346', '00360', '00388', '00410', '00417', '00422', '00426', '00437', '00444', '00446', '00470', '00471', '00480', '00486', '00499', '00506', '00514', '00537', '00553', '00559', '00581', '00597', '00614', '00615', '00638', '00648', '00649', '00652', '00659', '00681', '00686', '00700', '00703', '00726', '00731', '00741', '00755', '00768', '00783', '00831', '00855', '00860', '00863', '01026', '01029', '01036', '01041', '01053', '01079', '01092', '01102', '01125', '01129', '01132', '01136'.
We provide environments for both disassembly and assembly.
.. attention::
CUDA is required for running the Assembly environments.
Follow the below steps to install CUDA 12.8:
.. code-block:: bash
wget https://developer.download.nvidia.com/compute/cuda/12.8.0/local_installers/cuda_12.8.0_570.86.10_linux.run
sudo sh cuda_12.8.0_570.86.10_linux.run
For addition instructions and Windows installation, please refer to the `CUDA installation page <https://developer.nvidia.com/cuda-12-8-0-download-archive>`_.
* |disassembly-link|: The plug starts inserted in the socket. A low-level controller lifts th plug out and moves it to a random position. These trajectories serve as demonstrations for the reverse process, i.e., learning to assemble. To run disassembly for a specific task: ``./isaaclab.sh -p source/isaaclab_tasks/isaaclab_tasks/direct/assembly/run_disassembly_w_id.py --assembly_id=ASSEMBLY_ID``
* |assembly-link|: The goal is to insert the plug into the socket. You can use this environment to train a policy via reinforcement learning or evaluate a pre-trained checkpoint.
* To train an assembly policy: ``./isaaclab.sh -p source/isaaclab_tasks/isaaclab_tasks/direct/assembly/run_w_id.py --assembly_id=ASSEMBLY_ID --train``
* To evaluate an assembly policy: ``./isaaclab.sh -p source/isaaclab_tasks/isaaclab_tasks/direct/assembly/run_w_id.py --assembly_id=ASSEMBLY_ID --checkpoint=CHECKPOINT --log_eval``
.. table::
:widths: 33 37 30
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| World | Environment ID | Description |
+====================+=========================+=============================================================================+
| |disassembly| | |disassembly-link| | Lift a plug out of the socket with the Franka robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |assembly| | |assembly-link| | Insert a plug into its corresponding socket with the Franka robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
.. |assembly| image:: ../_static/tasks/assembly/00004.jpg
.. |disassembly| image:: ../_static/tasks/assembly/01053_disassembly.jpg
.. |assembly-link| replace:: `Isaac-Assembly-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/assembly/assembly_env_cfg.py>`__
.. |disassembly-link| replace:: `Isaac-Assembly-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_tasks/isaaclab_tasks/direct/assembly/disassembly_env_cfg.py>`__
Locomotion
~~~~~~~~~~
......@@ -667,6 +713,14 @@ Comprehensive List of Environments
-
- Direct
- **rl_games** (PPO)
* - Isaac-Assembly-Direct-v0
-
- Direct
- **rl_games** (PPO)
* - Isaac-Disassembly-Direct-v0
-
- Direct
-
* - Isaac-Franka-Cabinet-Direct-v0
-
- Direct
......
......@@ -19,4 +19,5 @@ def test_kit_start_up_time():
app_launcher = AppLauncher(headless=True).app # noqa: F841
end_time = time.time()
elapsed_time = end_time - start_time
assert elapsed_time <= 10.0
# we are doing some more imports on the automate side - will investigate using warp instead of numba cuda
assert elapsed_time <= 12.0
......@@ -15,6 +15,7 @@ simulation_app = app_launcher.app
"""Rest everything follows."""
import gymnasium as gym
import os
import torch
import carb
......@@ -31,12 +32,17 @@ from isaaclab_tasks.utils.parse_cfg import parse_env_cfg
@pytest.fixture(scope="module")
def registered_tasks():
# disable interactive mode for wandb for automate environments
os.environ["WANDB_DISABLED"] = "true"
# acquire all Isaac environments names
registered_tasks = list()
for task_spec in gym.registry.values():
if "Isaac" in task_spec.id:
cfg_entry_point = gym.spec(task_spec.id).kwargs.get("rl_games_cfg_entry_point")
if cfg_entry_point is not None:
# skip automate environments as they require cuda installation
if "assembly" in task_spec.id.lower():
continue
registered_tasks.append(task_spec.id)
# sort environments by name
registered_tasks.sort()
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.10.32"
version = "0.10.33"
# Description
title = "Isaac Lab Environments"
......
Changelog
---------
0.10.33 (2025-05-15)
~~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added ``Isaac-Assembly-Direct-v0`` environment as a direct RL env that
implements assembly tasks to insert pegs into their corresponding sockets.
0.10.32 (2025-05-21)
~~~~~~~~~~~~~~~~~~~~
......
# 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
from .assembly_env import AssemblyEnv, AssemblyEnvCfg
from .disassembly_env import DisassemblyEnv, DisassemblyEnvCfg
##
# Register Gym environments.
##
gym.register(
id="Isaac-Assembly-Direct-v0",
entry_point="isaaclab_tasks.direct.assembly:AssemblyEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": AssemblyEnvCfg,
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
},
)
gym.register(
id="Isaac-Disassembly-Direct-v0",
entry_point="isaaclab_tasks.direct.assembly:DisassemblyEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": DisassemblyEnvCfg,
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
},
)
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
params:
seed: 0
algo:
name: a2c_continuous
env:
clip_actions: 1.0
model:
name: continuous_a2c_logstd
network:
name: actor_critic
separate: False
space:
continuous:
mu_activation: None
sigma_activation: None
mu_init:
name: default
sigma_init:
name: const_initializer
val: 0
fixed_sigma: True
mlp:
units: [256, 128, 64]
activation: elu
d2rl: False
initializer:
name: default
regularizer:
name: None
rnn:
name: lstm
units: 256
layers: 2
before_mlp: True
concat_input: True
layer_norm: False
load_checkpoint: False
load_path: ""
config:
name: Assembly
device: cuda:0
full_experiment_name: test
env_name: rlgpu
multi_gpu: False
ppo: True
mixed_precision: True
normalize_input: True
normalize_value: True
value_bootstrap: True
num_actors: 128
reward_shaper:
scale_value: 1.0
normalize_advantage: True
gamma: 0.99
tau: 0.95
learning_rate: 1e-4
lr_schedule: fixed
schedule_type: standard
kl_threshold: 0.016
score_to_win: 20000
max_epochs: 1500
save_best_after: 100
save_frequency: 300
print_stats: True
grad_norm: 1.0
entropy_coef: 0.0
truncate_grads: False
e_clip: 0.2
horizon_length: 32
minibatch_size: 4096 # batch size = num_envs * horizon_length; minibatch_size = batch_size / num_minibatches
mini_epochs: 8
critic_coef: 2
clip_value: True
seq_length: 4
bounds_loss_coef: 0.0001
central_value_config:
minibatch_size: 256
mini_epochs: 4
learning_rate: 1e-3
lr_schedule: linear
kl_threshold: 0.016
clip_value: True
normalize_input: True
truncate_grads: True
network:
name: actor_critic
central_value: True
mlp:
units: [256, 128, 64]
activation: elu
d2rl: False
initializer:
name: default
regularizer:
name: None
player:
deterministic: False
# 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.actuator_cfg import ImplicitActuatorCfg
from isaaclab.assets import ArticulationCfg
from isaaclab.envs import DirectRLEnvCfg
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.sim import PhysxCfg, SimulationCfg
from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg
from isaaclab.utils import configclass
from .assembly_tasks_cfg import ASSET_DIR, Insertion
OBS_DIM_CFG = {
"joint_pos": 7,
"fingertip_pos": 3,
"fingertip_quat": 4,
"fingertip_goal_pos": 3,
"fingertip_goal_quat": 4,
"delta_pos": 3,
}
STATE_DIM_CFG = {
"joint_pos": 7,
"joint_vel": 7,
"fingertip_pos": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
"fingertip_goal_pos": 3,
"fingertip_goal_quat": 4,
"held_pos": 3,
"held_quat": 4,
"delta_pos": 3,
}
@configclass
class ObsRandCfg:
fixed_asset_pos = [0.001, 0.001, 0.001]
@configclass
class CtrlCfg:
ema_factor = 0.2
pos_action_bounds = [0.1, 0.1, 0.1]
rot_action_bounds = [0.01, 0.01, 0.01]
pos_action_threshold = [0.1, 0.1, 0.1]
rot_action_threshold = [0.01, 0.01, 0.01]
reset_joints = [0.0, 0.0, 0.0, -1.870, 0.0, 1.8675, 0.785398]
reset_task_prop_gains = [1000, 1000, 1000, 50, 50, 50]
# reset_rot_deriv_scale = 1.0
# default_task_prop_gains = [1000, 1000, 1000, 50, 50, 50]
# reset_task_prop_gains = [300, 300, 300, 20, 20, 20]
reset_rot_deriv_scale = 10.0
default_task_prop_gains = [100, 100, 100, 30, 30, 30]
# Null space parameters.
default_dof_pos_tensor = [0.0, 0.0, 0.0, -1.870, 0.0, 1.8675, 0.785398]
kp_null = 10.0
kd_null = 6.3246
@configclass
class AssemblyEnvCfg(DirectRLEnvCfg):
decimation = 8
action_space = 6
# num_*: will be overwritten to correspond to obs_order, state_order.
observation_space = 24
state_space = 44
obs_order: list = [
"joint_pos",
"fingertip_pos",
"fingertip_quat",
"fingertip_goal_pos",
"fingertip_goal_quat",
"delta_pos",
]
state_order: list = [
"joint_pos",
"joint_vel",
"fingertip_pos",
"fingertip_quat",
"ee_linvel",
"ee_angvel",
"fingertip_goal_pos",
"fingertip_goal_quat",
"held_pos",
"held_quat",
"delta_pos",
]
task_name: str = "insertion" # peg_insertion, gear_meshing, nut_threading
tasks: dict = {"insertion": Insertion()}
obs_rand: ObsRandCfg = ObsRandCfg()
ctrl: CtrlCfg = CtrlCfg()
# episode_length_s = 10.0 # Probably need to override.
episode_length_s = 5.0
sim: SimulationCfg = SimulationCfg(
device="cuda:0",
dt=1 / 120,
gravity=(0.0, 0.0, -9.81),
physx=PhysxCfg(
solver_type=1,
max_position_iteration_count=192, # Important to avoid interpenetration.
max_velocity_iteration_count=1,
bounce_threshold_velocity=0.2,
friction_offset_threshold=0.01,
friction_correlation_distance=0.00625,
gpu_max_rigid_contact_count=2**23,
gpu_max_rigid_patch_count=2**23,
gpu_max_num_partitions=1, # Important for stable simulation.
),
physics_material=RigidBodyMaterialCfg(
static_friction=1.0,
dynamic_friction=1.0,
),
)
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=128, env_spacing=2.0)
robot = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ASSET_DIR}/franka_mimic.usd",
# usd_path=f'{ASSET_DIR}/automate_franka.usd',
activate_contact_sensors=False,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
init_state=ArticulationCfg.InitialStateCfg(
joint_pos={
"panda_joint1": 0.00871,
"panda_joint2": -0.10368,
"panda_joint3": -0.00794,
"panda_joint4": -1.49139,
"panda_joint5": -0.00083,
"panda_joint6": 1.38774,
"panda_joint7": 0.0,
"panda_finger_joint2": 0.04,
},
pos=(0.0, 0.0, 0.0),
rot=(1.0, 0.0, 0.0, 0.0),
),
actuators={
"panda_arm1": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[1-4]"],
stiffness=0.0,
damping=0.0,
friction=0.0,
armature=0.0,
effort_limit=87,
velocity_limit=124.6,
),
"panda_arm2": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"],
stiffness=0.0,
damping=0.0,
friction=0.0,
armature=0.0,
effort_limit=12,
velocity_limit=149.5,
),
"panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint[1-2]"],
effort_limit=40.0,
velocity_limit=0.04,
stiffness=7500.0,
damping=173.0,
friction=0.1,
armature=0.0,
),
},
)
# contact_sensor: ContactSensorCfg = ContactSensorCfg(
# prim_path="/World/envs/env_.*/Robot/.*", update_period=0.0, history_length=1, debug_vis=True
# )
# 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.assets import ArticulationCfg, RigidObjectCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR
ASSET_DIR = f"{ISAACLAB_NUCLEUS_DIR}/AutoMate"
OBS_DIM_CFG = {
"fingertip_pos": 3,
"fingertip_pos_rel_fixed": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
}
STATE_DIM_CFG = {
"fingertip_pos": 3,
"fingertip_pos_rel_fixed": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
"joint_pos": 7,
"held_pos": 3,
"held_pos_rel_fixed": 3,
"held_quat": 4,
"fixed_pos": 3,
"fixed_quat": 4,
"task_prop_gains": 6,
"ema_factor": 1,
"pos_threshold": 3,
"rot_threshold": 3,
}
@configclass
class FixedAssetCfg:
usd_path: str = ""
diameter: float = 0.0
height: float = 0.0
base_height: float = 0.0 # Used to compute held asset CoM.
friction: float = 0.75
mass: float = 0.05
@configclass
class HeldAssetCfg:
usd_path: str = ""
diameter: float = 0.0 # Used for gripper width.
height: float = 0.0
friction: float = 0.75
mass: float = 0.05
@configclass
class RobotCfg:
robot_usd: str = ""
franka_fingerpad_length: float = 0.017608
friction: float = 0.75
@configclass
class AssemblyTask:
robot_cfg: RobotCfg = RobotCfg()
name: str = ""
duration_s = 5.0
fixed_asset_cfg: FixedAssetCfg = FixedAssetCfg()
held_asset_cfg: HeldAssetCfg = HeldAssetCfg()
asset_size: float = 0.0
# palm_to_finger_dist: float = 0.1034
palm_to_finger_dist: float = 0.1134
# Robot
hand_init_pos: list = [0.0, 0.0, 0.015] # Relative to fixed asset tip.
hand_init_pos_noise: list = [0.02, 0.02, 0.01]
hand_init_orn: list = [3.1416, 0, 2.356]
hand_init_orn_noise: list = [0.0, 0.0, 1.57]
# Action
unidirectional_rot: bool = False
# Fixed Asset (applies to all tasks)
fixed_asset_init_pos_noise: list = [0.05, 0.05, 0.05]
fixed_asset_init_orn_deg: float = 0.0
fixed_asset_init_orn_range_deg: float = 10.0
# Held Asset (applies to all tasks)
# held_asset_pos_noise: list = [0.0, 0.006, 0.003] # noise level of the held asset in gripper
held_asset_init_pos_noise: list = [0.01, 0.01, 0.01]
held_asset_pos_noise: list = [0.0, 0.0, 0.0]
held_asset_rot_init: float = 0.0
# Reward
ee_success_yaw: float = 0.0 # nut_threading task only.
action_penalty_scale: float = 0.0
action_grad_penalty_scale: float = 0.0
# Reward function details can be found in Appendix B of https://arxiv.org/pdf/2408.04587.
# Multi-scale keypoints are used to capture different phases of the task.
# Each reward passes the keypoint distance, x, through a squashing function:
# r(x) = 1/(exp(-ax) + b + exp(ax)).
# Each list defines [a, b] which control the slope and maximum of the squashing function.
num_keypoints: int = 4
keypoint_scale: float = 0.15
# Fixed-asset height fraction for which different bonuses are rewarded (see individual tasks).
success_threshold: float = 0.04
engage_threshold: float = 0.9
# SDF reward
sdf_rwd_scale: float = 1.0
num_mesh_sample_points: int = 1000
# Imitation reward
imitation_rwd_scale: float = 1.0
soft_dtw_gamma: float = 0.01 # set to 0 if want to use the original DTW without any smoothing
num_point_robot_traj: int = 10 # number of waypoints included in the end-effector trajectory
# SBC
initial_max_disp: float = 0.01 # max initial downward displacement of plug at beginning of curriculum
curriculum_success_thresh: float = 0.8 # success rate threshold for increasing curriculum difficulty
curriculum_failure_thresh: float = 0.5 # success rate threshold for decreasing curriculum difficulty
curriculum_freespace_range: float = 0.01
num_curriculum_step: int = 10
curriculum_height_step: list = [
-0.005,
0.003,
] # how much to increase max initial downward displacement after hitting success or failure thresh
if_sbc: bool = True
# Logging evaluation results
if_logging_eval: bool = False
num_eval_trials: int = 100
eval_filename: str = "evaluation_00015.h5"
# Fine-tuning
sample_from: str = "rand" # gp, gmm, idv, rand
num_gp_candidates: int = 1000
@configclass
class Peg8mm(HeldAssetCfg):
usd_path = "plug.usd"
obj_path = "plug.obj"
diameter = 0.007986
height = 0.050
mass = 0.019
@configclass
class Hole8mm(FixedAssetCfg):
usd_path = "socket.usd"
obj_path = "socket.obj"
diameter = 0.0081
height = 0.050896
base_height = 0.0
@configclass
class Insertion(AssemblyTask):
name = "insertion"
assembly_id = "00015"
assembly_dir = f"{ASSET_DIR}/{assembly_id}/"
fixed_asset_cfg = Hole8mm()
held_asset_cfg = Peg8mm()
asset_size = 8.0
duration_s = 10.0
plug_grasp_json = f"{ASSET_DIR}/plug_grasps.json"
disassembly_dist_json = f"{ASSET_DIR}/disassembly_dist.json"
disassembly_path_json = f"{assembly_dir}/disassemble_traj.json"
# Robot
hand_init_pos: list = [0.0, 0.0, 0.047] # Relative to fixed asset tip.
hand_init_pos_noise: list = [0.02, 0.02, 0.01]
hand_init_orn: list = [3.1416, 0.0, 0.0]
hand_init_orn_noise: list = [0.0, 0.0, 0.785]
hand_width_max: float = 0.080 # maximum opening width of gripper
# Fixed Asset (applies to all tasks)
fixed_asset_init_pos_noise: list = [0.05, 0.05, 0.05]
fixed_asset_init_orn_deg: float = 0.0
fixed_asset_init_orn_range_deg: float = 10.0
fixed_asset_z_offset: float = 0.1435
# Held Asset (applies to all tasks)
# held_asset_pos_noise: list = [0.003, 0.0, 0.003] # noise level of the held asset in gripper
held_asset_init_pos_noise: list = [0.01, 0.01, 0.01]
held_asset_pos_noise: list = [0.0, 0.0, 0.0]
held_asset_rot_init: float = 0.0
# Rewards
keypoint_coef_baseline: list = [5, 4]
keypoint_coef_coarse: list = [50, 2]
keypoint_coef_fine: list = [100, 0]
# Fraction of socket height.
success_threshold: float = 0.04
engage_threshold: float = 0.9
engage_height_thresh: float = 0.01
success_height_thresh: float = 0.003
close_error_thresh: float = 0.015
fixed_asset: ArticulationCfg = ArticulationCfg(
# fixed_asset: RigidObjectCfg = RigidObjectCfg(
prim_path="/World/envs/env_.*/FixedAsset",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{assembly_dir}{fixed_asset_cfg.usd_path}",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
fix_root_link=True, # add this so the fixed asset is set to have a fixed base
),
mass_props=sim_utils.MassPropertiesCfg(mass=fixed_asset_cfg.mass),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
init_state=ArticulationCfg.InitialStateCfg(
# init_state=RigidObjectCfg.InitialStateCfg(
pos=(0.6, 0.0, 0.05),
rot=(1.0, 0.0, 0.0, 0.0),
joint_pos={},
joint_vel={},
),
actuators={},
)
# held_asset: ArticulationCfg = ArticulationCfg(
held_asset: RigidObjectCfg = RigidObjectCfg(
prim_path="/World/envs/env_.*/HeldAsset",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{assembly_dir}{held_asset_cfg.usd_path}",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
# init_state=ArticulationCfg.InitialStateCfg(
init_state=RigidObjectCfg.InitialStateCfg(
pos=(0.0, 0.4, 0.1),
rot=(1.0, 0.0, 0.0, 0.0),
# joint_pos={},
# joint_vel={}
),
# actuators={}
)
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import h5py
def write_log_to_hdf5(held_asset_pose_log, fixed_asset_pose_log, success_log, eval_logging_filename):
with h5py.File(eval_logging_filename, "w") as hf:
hf.create_dataset("held_asset_pose", data=held_asset_pose_log.cpu().numpy())
hf.create_dataset("fixed_asset_pose", data=fixed_asset_pose_log.cpu().numpy())
hf.create_dataset("success", data=success_log.cpu().numpy())
def load_log_from_hdf5(eval_logging_filename):
with h5py.File(eval_logging_filename, "r") as hf:
held_asset_pose = hf["held_asset_pose"][:]
fixed_asset_pose = hf["fixed_asset_pose"][:]
success = hf["success"][:]
# held_asset_pose = torch.from_numpy(held_asset_pose).to(device)
# fixed_asset_pose = torch.from_numpy(fixed_asset_pose).to(device)
# success = torch.from_numpy(success).to(device)
return held_asset_pose, fixed_asset_pose, success
# 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.actuator_cfg import ImplicitActuatorCfg
from isaaclab.assets import ArticulationCfg
from isaaclab.envs import DirectRLEnvCfg
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.sim import PhysxCfg, SimulationCfg
from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg
from isaaclab.utils import configclass
from .disassembly_tasks_cfg import ASSET_DIR, Extraction
OBS_DIM_CFG = {
"joint_pos": 7,
"fingertip_pos": 3,
"fingertip_quat": 4,
"fingertip_goal_pos": 3,
"fingertip_goal_quat": 4,
"delta_pos": 3,
}
STATE_DIM_CFG = {
"joint_pos": 7,
"joint_vel": 7,
"fingertip_pos": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
"fingertip_goal_pos": 3,
"fingertip_goal_quat": 4,
"held_pos": 3,
"held_quat": 4,
"delta_pos": 3,
}
@configclass
class ObsRandCfg:
fixed_asset_pos = [0.001, 0.001, 0.001]
@configclass
class CtrlCfg:
ema_factor = 0.2
pos_action_bounds = [0.1, 0.1, 0.1]
rot_action_bounds = [0.01, 0.01, 0.01]
pos_action_threshold = [0.01, 0.01, 0.01]
rot_action_threshold = [0.01, 0.01, 0.01]
reset_joints = [0.0, 0.0, 0.0, -1.870, 0.0, 1.8675, 0.785398]
reset_task_prop_gains = [1000, 1000, 1000, 50, 50, 50]
# reset_rot_deriv_scale = 1.0
# default_task_prop_gains = [1000, 1000, 1000, 50, 50, 50]
# reset_task_prop_gains = [300, 300, 300, 20, 20, 20]
reset_rot_deriv_scale = 10.0
default_task_prop_gains = [100, 100, 100, 30, 30, 30]
# Null space parameters.
default_dof_pos_tensor = [0.0, 0.0, 0.0, -1.870, 0.0, 1.8675, 0.785398]
kp_null = 10.0
kd_null = 6.3246
@configclass
class DisassemblyEnvCfg(DirectRLEnvCfg):
decimation = 8
action_space = 6
# num_*: will be overwritten to correspond to obs_order, state_order.
observation_space = 24
state_space = 44
obs_order: list = [
"joint_pos",
"fingertip_pos",
"fingertip_quat",
"fingertip_goal_pos",
"fingertip_goal_quat",
"delta_pos",
]
state_order: list = [
"joint_pos",
"joint_vel",
"fingertip_pos",
"fingertip_quat",
"ee_linvel",
"ee_angvel",
"fingertip_goal_pos",
"fingertip_goal_quat",
"held_pos",
"held_quat",
"delta_pos",
]
task_name: str = "extraction" # peg_insertion, gear_meshing, nut_threading
tasks: dict = {"extraction": Extraction()}
obs_rand: ObsRandCfg = ObsRandCfg()
ctrl: CtrlCfg = CtrlCfg()
# episode_length_s = 10.0 # Probably need to override.
episode_length_s = 5.0
sim: SimulationCfg = SimulationCfg(
device="cuda:0",
dt=1 / 120,
gravity=(0.0, 0.0, -9.81),
physx=PhysxCfg(
solver_type=1,
max_position_iteration_count=192, # Important to avoid interpenetration.
max_velocity_iteration_count=1,
bounce_threshold_velocity=0.2,
friction_offset_threshold=0.01,
friction_correlation_distance=0.00625,
gpu_max_rigid_contact_count=2**23,
gpu_max_rigid_patch_count=2**23,
gpu_max_num_partitions=1, # Important for stable simulation.
),
physics_material=RigidBodyMaterialCfg(
static_friction=1.0,
dynamic_friction=1.0,
),
)
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=128, env_spacing=2.0)
robot = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ASSET_DIR}/franka_mimic.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
init_state=ArticulationCfg.InitialStateCfg(
joint_pos={
"panda_joint1": 0.00871,
"panda_joint2": -0.10368,
"panda_joint3": -0.00794,
"panda_joint4": -1.49139,
"panda_joint5": -0.00083,
"panda_joint6": 1.38774,
"panda_joint7": 0.0,
"panda_finger_joint2": 0.04,
},
pos=(0.0, 0.0, 0.0),
rot=(1.0, 0.0, 0.0, 0.0),
),
actuators={
"panda_arm1": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[1-4]"],
stiffness=0.0,
damping=0.0,
friction=0.0,
armature=0.0,
effort_limit=87,
velocity_limit=124.6,
),
"panda_arm2": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"],
stiffness=0.0,
damping=0.0,
friction=0.0,
armature=0.0,
effort_limit=12,
velocity_limit=149.5,
),
"panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint[1-2]"],
effort_limit=40.0,
velocity_limit=0.04,
stiffness=7500.0,
damping=173.0,
friction=0.1,
armature=0.0,
),
},
)
# 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.assets import ArticulationCfg, RigidObjectCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR
ASSET_DIR = f"{ISAACLAB_NUCLEUS_DIR}/AutoMate"
OBS_DIM_CFG = {
"fingertip_pos": 3,
"fingertip_pos_rel_fixed": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
}
STATE_DIM_CFG = {
"fingertip_pos": 3,
"fingertip_pos_rel_fixed": 3,
"fingertip_quat": 4,
"ee_linvel": 3,
"ee_angvel": 3,
"joint_pos": 7,
"held_pos": 3,
"held_pos_rel_fixed": 3,
"held_quat": 4,
"fixed_pos": 3,
"fixed_quat": 4,
"task_prop_gains": 6,
"ema_factor": 1,
"pos_threshold": 3,
"rot_threshold": 3,
}
@configclass
class FixedAssetCfg:
usd_path: str = ""
diameter: float = 0.0
height: float = 0.0
base_height: float = 0.0 # Used to compute held asset CoM.
friction: float = 0.75
mass: float = 0.05
@configclass
class HeldAssetCfg:
usd_path: str = ""
diameter: float = 0.0 # Used for gripper width.
height: float = 0.0
friction: float = 0.75
mass: float = 0.05
@configclass
class RobotCfg:
robot_usd: str = ""
franka_fingerpad_length: float = 0.017608
friction: float = 0.75
@configclass
class DisassemblyTask:
robot_cfg: RobotCfg = RobotCfg()
name: str = ""
duration_s = 5.0
fixed_asset_cfg: FixedAssetCfg = FixedAssetCfg()
held_asset_cfg: HeldAssetCfg = HeldAssetCfg()
asset_size: float = 0.0
# palm_to_finger_dist: float = 0.1034
palm_to_finger_dist: float = 0.1134
# Robot
hand_init_pos: list = [0.0, 0.0, 0.015] # Relative to fixed asset tip.
hand_init_pos_noise: list = [0.02, 0.02, 0.01]
hand_init_orn: list = [3.1416, 0, 2.356]
hand_init_orn_noise: list = [0.0, 0.0, 1.57]
# Action
unidirectional_rot: bool = False
# Fixed Asset (applies to all tasks)
fixed_asset_init_pos_noise: list = [0.05, 0.05, 0.05]
fixed_asset_init_orn_deg: float = 0.0
fixed_asset_init_orn_range_deg: float = 10.0
num_point_robot_traj: int = 10 # number of waypoints included in the end-effector trajectory
@configclass
class Peg8mm(HeldAssetCfg):
usd_path = "plug.usd"
obj_path = "plug.obj"
diameter = 0.007986
height = 0.050
mass = 0.019
@configclass
class Hole8mm(FixedAssetCfg):
usd_path = "socket.usd"
obj_path = "socket.obj"
diameter = 0.0081
height = 0.050896
base_height = 0.0
@configclass
class Extraction(DisassemblyTask):
name = "extraction"
assembly_id = "00731"
assembly_dir = f"{ASSET_DIR}/{assembly_id}/"
disassembly_dir = "disassembly_dir"
num_log_traj = 100
fixed_asset_cfg = Hole8mm()
held_asset_cfg = Peg8mm()
asset_size = 8.0
duration_s = 10.0
plug_grasp_json = f"{ASSET_DIR}/plug_grasps.json"
disassembly_dist_json = f"{ASSET_DIR}/disassembly_dist.json"
move_gripper_sim_steps = 64
disassemble_sim_steps = 64
# Robot
hand_init_pos: list = [0.0, 0.0, 0.047] # Relative to fixed asset tip.
hand_init_pos_noise: list = [0.02, 0.02, 0.01]
hand_init_orn: list = [3.1416, 0.0, 0.0]
hand_init_orn_noise: list = [0.0, 0.0, 0.785]
hand_width_max: float = 0.080 # maximum opening width of gripper
# Fixed Asset (applies to all tasks)
fixed_asset_init_pos_noise: list = [0.05, 0.05, 0.05]
fixed_asset_init_orn_deg: float = 0.0
fixed_asset_init_orn_range_deg: float = 10.0
fixed_asset_z_offset: float = 0.1435
fingertip_centered_pos_initial: list = [
0.0,
0.0,
0.2,
] # initial position of midpoint between fingertips above table
fingertip_centered_rot_initial: list = [3.141593, 0.0, 0.0] # initial rotation of fingertips (Euler)
gripper_rand_pos_noise: list = [0.05, 0.05, 0.05]
gripper_rand_rot_noise: list = [0.174533, 0.174533, 0.174533] # +-10 deg for roll/pitch/yaw
gripper_rand_z_offset: float = 0.05
fixed_asset: ArticulationCfg = ArticulationCfg(
# fixed_asset: RigidObjectCfg = RigidObjectCfg(
prim_path="/World/envs/env_.*/FixedAsset",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{assembly_dir}{fixed_asset_cfg.usd_path}",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
fix_root_link=True, # add this so the fixed asset is set to have a fixed base
),
mass_props=sim_utils.MassPropertiesCfg(mass=fixed_asset_cfg.mass),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
init_state=ArticulationCfg.InitialStateCfg(
# init_state=RigidObjectCfg.InitialStateCfg(
pos=(0.6, 0.0, 0.05),
rot=(1.0, 0.0, 0.0, 0.0),
joint_pos={},
joint_vel={},
),
actuators={},
)
# held_asset: ArticulationCfg = ArticulationCfg(
held_asset: RigidObjectCfg = RigidObjectCfg(
prim_path="/World/envs/env_.*/HeldAsset",
spawn=sim_utils.UsdFileCfg(
usd_path=f"{assembly_dir}{held_asset_cfg.usd_path}",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
max_depenetration_velocity=5.0,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=3666.0,
enable_gyroscopic_forces=True,
solver_position_iteration_count=192,
solver_velocity_iteration_count=1,
max_contact_impulse=1e32,
),
mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass),
collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
# init_state=ArticulationCfg.InitialStateCfg(
init_state=RigidObjectCfg.InitialStateCfg(
pos=(0.0, 0.4, 0.1),
rot=(1.0, 0.0, 0.0, 0.0),
# joint_pos={},
# joint_vel={}
),
# actuators={}
)
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Factory: control module.
Imported by base, environment, and task classes. Not directly executed.
"""
import math
import torch
import isaacsim.core.utils.torch as torch_utils
from isaaclab.utils.math import axis_angle_from_quat
def compute_dof_torque(
cfg,
dof_pos,
dof_vel,
fingertip_midpoint_pos,
fingertip_midpoint_quat,
fingertip_midpoint_linvel,
fingertip_midpoint_angvel,
jacobian,
arm_mass_matrix,
ctrl_target_fingertip_midpoint_pos,
ctrl_target_fingertip_midpoint_quat,
task_prop_gains,
task_deriv_gains,
device,
):
"""Compute Franka DOF torque to move fingertips towards target pose."""
# References:
# 1) https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2018/RD_HS2018script.pdf
# 2) Modern Robotics
num_envs = cfg.scene.num_envs
dof_torque = torch.zeros((num_envs, dof_pos.shape[1]), device=device)
task_wrench = torch.zeros((num_envs, 6), device=device)
pos_error, axis_angle_error = get_pose_error(
fingertip_midpoint_pos=fingertip_midpoint_pos,
fingertip_midpoint_quat=fingertip_midpoint_quat,
ctrl_target_fingertip_midpoint_pos=ctrl_target_fingertip_midpoint_pos,
ctrl_target_fingertip_midpoint_quat=ctrl_target_fingertip_midpoint_quat,
jacobian_type="geometric",
rot_error_type="axis_angle",
)
delta_fingertip_pose = torch.cat((pos_error, axis_angle_error), dim=1)
# Set tau = k_p * task_pos_error - k_d * task_vel_error (building towards eq. 3.96-3.98)
task_wrench_motion = _apply_task_space_gains(
delta_fingertip_pose=delta_fingertip_pose,
fingertip_midpoint_linvel=fingertip_midpoint_linvel,
fingertip_midpoint_angvel=fingertip_midpoint_angvel,
task_prop_gains=task_prop_gains,
task_deriv_gains=task_deriv_gains,
)
task_wrench += task_wrench_motion
# Set tau = J^T * tau, i.e., map tau into joint space as desired
jacobian_T = torch.transpose(jacobian, dim0=1, dim1=2)
dof_torque[:, 0:7] = (jacobian_T @ task_wrench.unsqueeze(-1)).squeeze(-1)
# adapted from https://gitlab-master.nvidia.com/carbon-gym/carbgym/-/blob/b4bbc66f4e31b1a1bee61dbaafc0766bbfbf0f58/python/examples/franka_cube_ik_osc.py#L70-78
# roboticsproceedings.org/rss07/p31.pdf
# useful tensors
arm_mass_matrix_inv = torch.inverse(arm_mass_matrix)
jacobian_T = torch.transpose(jacobian, dim0=1, dim1=2)
arm_mass_matrix_task = torch.inverse(
jacobian @ torch.inverse(arm_mass_matrix) @ jacobian_T
) # ETH eq. 3.86; geometric Jacobian is assumed
j_eef_inv = arm_mass_matrix_task @ jacobian @ arm_mass_matrix_inv
default_dof_pos_tensor = torch.tensor(cfg.ctrl.default_dof_pos_tensor, device=device).repeat((num_envs, 1))
# nullspace computation
distance_to_default_dof_pos = default_dof_pos_tensor - dof_pos[:, :7]
distance_to_default_dof_pos = (distance_to_default_dof_pos + math.pi) % (
2 * math.pi
) - math.pi # normalize to [-pi, pi]
u_null = cfg.ctrl.kd_null * -dof_vel[:, :7] + cfg.ctrl.kp_null * distance_to_default_dof_pos
u_null = arm_mass_matrix @ u_null.unsqueeze(-1)
torque_null = (torch.eye(7, device=device).unsqueeze(0) - torch.transpose(jacobian, 1, 2) @ j_eef_inv) @ u_null
dof_torque[:, 0:7] += torque_null.squeeze(-1)
# TODO: Verify it's okay to no longer do gripper control here.
dof_torque = torch.clamp(dof_torque, min=-100.0, max=100.0)
return dof_torque, task_wrench
def get_pose_error(
fingertip_midpoint_pos,
fingertip_midpoint_quat,
ctrl_target_fingertip_midpoint_pos,
ctrl_target_fingertip_midpoint_quat,
jacobian_type,
rot_error_type,
):
"""Compute task-space error between target Franka fingertip pose and current pose."""
# Reference: https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2018/RD_HS2018script.pdf
# Compute pos error
pos_error = ctrl_target_fingertip_midpoint_pos - fingertip_midpoint_pos
# Compute rot error
if jacobian_type == "geometric": # See example 2.9.8; note use of J_g and transformation between rotation vectors
# Compute quat error (i.e., difference quat)
# Reference: https://personal.utdallas.edu/~sxb027100/dock/quat.html
# Check for shortest path using quaternion dot product.
quat_dot = (ctrl_target_fingertip_midpoint_quat * fingertip_midpoint_quat).sum(dim=1, keepdim=True)
ctrl_target_fingertip_midpoint_quat = torch.where(
quat_dot.expand(-1, 4) >= 0, ctrl_target_fingertip_midpoint_quat, -ctrl_target_fingertip_midpoint_quat
)
fingertip_midpoint_quat_norm = torch_utils.quat_mul(
fingertip_midpoint_quat, torch_utils.quat_conjugate(fingertip_midpoint_quat)
)[
:, 0
] # scalar component
fingertip_midpoint_quat_inv = torch_utils.quat_conjugate(
fingertip_midpoint_quat
) / fingertip_midpoint_quat_norm.unsqueeze(-1)
quat_error = torch_utils.quat_mul(ctrl_target_fingertip_midpoint_quat, fingertip_midpoint_quat_inv)
# Convert to axis-angle error
axis_angle_error = axis_angle_from_quat(quat_error)
if rot_error_type == "quat":
return pos_error, quat_error
elif rot_error_type == "axis_angle":
return pos_error, axis_angle_error
def _get_delta_dof_pos(delta_pose, ik_method, jacobian, device):
"""Get delta Franka DOF position from delta pose using specified IK method."""
# References:
# 1) https://www.cs.cmu.edu/~15464-s13/lectures/lecture6/iksurvey.pdf
# 2) https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2018/RD_HS2018script.pdf (p. 47)
if ik_method == "pinv": # Jacobian pseudoinverse
k_val = 1.0
jacobian_pinv = torch.linalg.pinv(jacobian)
delta_dof_pos = k_val * jacobian_pinv @ delta_pose.unsqueeze(-1)
delta_dof_pos = delta_dof_pos.squeeze(-1)
elif ik_method == "trans": # Jacobian transpose
k_val = 1.0
jacobian_T = torch.transpose(jacobian, dim0=1, dim1=2)
delta_dof_pos = k_val * jacobian_T @ delta_pose.unsqueeze(-1)
delta_dof_pos = delta_dof_pos.squeeze(-1)
elif ik_method == "dls": # damped least squares (Levenberg-Marquardt)
lambda_val = 0.1 # 0.1
jacobian_T = torch.transpose(jacobian, dim0=1, dim1=2)
lambda_matrix = (lambda_val**2) * torch.eye(n=jacobian.shape[1], device=device)
delta_dof_pos = jacobian_T @ torch.inverse(jacobian @ jacobian_T + lambda_matrix) @ delta_pose.unsqueeze(-1)
delta_dof_pos = delta_dof_pos.squeeze(-1)
elif ik_method == "svd": # adaptive SVD
k_val = 1.0
U, S, Vh = torch.linalg.svd(jacobian)
S_inv = 1.0 / S
min_singular_value = 1.0e-5
S_inv = torch.where(S > min_singular_value, S_inv, torch.zeros_like(S_inv))
jacobian_pinv = (
torch.transpose(Vh, dim0=1, dim1=2)[:, :, :6] @ torch.diag_embed(S_inv) @ torch.transpose(U, dim0=1, dim1=2)
)
delta_dof_pos = k_val * jacobian_pinv @ delta_pose.unsqueeze(-1)
delta_dof_pos = delta_dof_pos.squeeze(-1)
return delta_dof_pos
def _apply_task_space_gains(
delta_fingertip_pose, fingertip_midpoint_linvel, fingertip_midpoint_angvel, task_prop_gains, task_deriv_gains
):
"""Interpret PD gains as task-space gains. Apply to task-space error."""
task_wrench = torch.zeros_like(delta_fingertip_pose)
# Apply gains to lin error components
lin_error = delta_fingertip_pose[:, 0:3]
task_wrench[:, 0:3] = task_prop_gains[:, 0:3] * lin_error + task_deriv_gains[:, 0:3] * (
0.0 - fingertip_midpoint_linvel
)
# Apply gains to rot error components
rot_error = delta_fingertip_pose[:, 3:6]
task_wrench[:, 3:6] = task_prop_gains[:, 3:6] * rot_error + task_deriv_gains[:, 3:6] * (
0.0 - fingertip_midpoint_angvel
)
return task_wrench
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import argparse
import os
import re
import subprocess
def update_task_param(task_cfg, assembly_id, disassembly_dir):
# Read the file lines.
with open(task_cfg) as f:
lines = f.readlines()
updated_lines = []
# Regex patterns to capture the assignment lines
assembly_pattern = re.compile(r"^(.*assembly_id\s*=\s*).*$")
disassembly_dir_pattern = re.compile(r"^(.*disassembly_dir\s*=\s*).*$")
for line in lines:
if "assembly_id =" in line:
line = assembly_pattern.sub(rf"\1'{assembly_id}'", line)
elif "disassembly_dir = " in line:
line = disassembly_dir_pattern.sub(rf"\1'{disassembly_dir}'", line)
updated_lines.append(line)
# Write the modified lines back to the file.
with open(task_cfg, "w") as f:
f.writelines(updated_lines)
def main():
parser = argparse.ArgumentParser(description="Update assembly_id and run training script.")
parser.add_argument(
"--disassembly_dir",
type=str,
help="Path to the directory containing output disassembly trajectories.",
default="disassembly_dir",
)
parser.add_argument(
"--cfg_path",
type=str,
help="Path to the file containing assembly_id.",
default="source/isaaclab_tasks/isaaclab_tasks/direct/assembly/disassembly_tasks_cfg.py",
)
parser.add_argument("--assembly_id", type=str, default="00731", help="New assembly ID to set.")
parser.add_argument("--num_envs", type=int, default=128, help="Number of parallel environment.")
parser.add_argument("--seed", type=int, default=-1, help="Random seed.")
parser.add_argument("--headless", action="store_true", help="Run in headless mode.")
args = parser.parse_args()
os.makedirs(args.disassembly_dir, exist_ok=True)
update_task_param(
args.cfg_path,
args.assembly_id,
args.disassembly_dir,
)
bash_command = (
"./isaaclab.sh -p scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Disassembly-Direct-v0"
)
bash_command += f" --num_envs={str(args.num_envs)}"
bash_command += f" --seed={str(args.seed)}"
if args.headless:
bash_command += " --headless"
# Run the bash command
subprocess.run(bash_command, shell=True, check=True)
if __name__ == "__main__":
main()
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import argparse
import re
import subprocess
def update_task_param(task_cfg, assembly_id, if_sbc, if_log_eval):
# Read the file lines.
with open(task_cfg) as f:
lines = f.readlines()
updated_lines = []
# Regex patterns to capture the assignment lines
assembly_pattern = re.compile(r"^(.*assembly_id\s*=\s*).*$")
if_sbc_pattern = re.compile(r"^(.*if_sbc\s*:\s*bool\s*=\s*).*$")
if_log_eval_pattern = re.compile(r"^(.*if_logging_eval\s*:\s*bool\s*=\s*).*$")
eval_file_pattern = re.compile(r"^(.*eval_filename\s*:\s*str\s*=\s*).*$")
for line in lines:
if "assembly_id =" in line:
line = assembly_pattern.sub(rf"\1'{assembly_id}'", line)
elif "if_sbc: bool =" in line:
line = if_sbc_pattern.sub(rf"\1{str(if_sbc)}", line)
elif "if_logging_eval: bool =" in line:
line = if_log_eval_pattern.sub(rf"\1{str(if_log_eval)}", line)
elif "eval_filename: str = " in line:
line = eval_file_pattern.sub(r"\1'{}'".format(f"evaluation_{assembly_id}.h5"), line)
updated_lines.append(line)
# Write the modified lines back to the file.
with open(task_cfg, "w") as f:
f.writelines(updated_lines)
def main():
parser = argparse.ArgumentParser(description="Update assembly_id and run training script.")
parser.add_argument(
"--cfg_path",
type=str,
help="Path to the file containing assembly_id.",
default="source/isaaclab_tasks/isaaclab_tasks/direct/assembly/assembly_tasks_cfg.py",
)
parser.add_argument("--assembly_id", type=str, help="New assembly ID to set.")
parser.add_argument("--checkpoint", type=str, help="Checkpoint path.")
parser.add_argument("--num_envs", type=int, default=128, help="Number of parallel environment.")
parser.add_argument("--seed", type=int, default=-1, help="Random seed.")
parser.add_argument("--train", action="store_true", help="Run training mode.")
parser.add_argument("--log_eval", action="store_true", help="Log evaluation results.")
parser.add_argument("--headless", action="store_true", help="Run in headless mode.")
args = parser.parse_args()
update_task_param(args.cfg_path, args.assembly_id, args.train, args.log_eval)
bash_command = None
if args.train:
bash_command = (
"./isaaclab.sh -p scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Assembly-Direct-v0"
)
bash_command += f" --seed={str(args.seed)}"
else:
if not args.checkpoint:
raise ValueError("No checkpoint provided for evaluation.")
bash_command = (
"./isaaclab.sh -p scripts/reinforcement_learning/rl_games/play.py --task=Isaac-Assembly-Direct-v0"
)
bash_command += f" --num_envs={str(args.num_envs)}"
if args.checkpoint:
bash_command += f" --checkpoint={args.checkpoint}"
if args.headless:
bash_command += " --headless"
# Run the bash command
subprocess.run(bash_command, shell=True, check=True)
if __name__ == "__main__":
main()
......@@ -26,6 +26,8 @@ INSTALL_REQUIRES = [
"protobuf>=3.20.2, < 5.0.0",
# basic logger
"tensorboard",
# automate
"scikit-learn",
]
PYTORCH_INDEX_URL = ["https://download.pytorch.org/whl/cu118"]
......
......@@ -25,6 +25,7 @@ simulation_app = app_launcher.app
"""Rest everything follows."""
import gymnasium as gym
import os
import torch
import carb
......@@ -40,6 +41,8 @@ from isaaclab_tasks.utils.parse_cfg import parse_env_cfg
# @pytest.fixture(scope="module", autouse=True)
def setup_environment():
# disable interactive mode for wandb for automate environments
os.environ["WANDB_DISABLED"] = "true"
# acquire all Isaac environments names
registered_tasks = list()
for task_spec in gym.registry.values():
......@@ -68,6 +71,12 @@ def test_environments(task_name, num_envs, device):
"Isaac-Stack-Cube-Franka-IK-Rel-Visuomotor-v0",
]:
return
# skip automate environments as they require cuda installation
if task_name in ["Isaac-Assembly-Direct-v0", "Isaac-Disassembly-Direct-v0"]:
return
# skipping this test for now as it requires torch 2.6 or newer
if task_name == "Isaac-Cartpole-RGB-TheiaTiny-v0":
return
print(f">>> Running test for environment: {task_name}")
_check_random_actions(task_name, device, num_envs, num_steps=100)
print(f">>> Closing environment: {task_name}")
......
......@@ -18,6 +18,7 @@ DEFAULT_TIMEOUT = 120
PER_TEST_TIMEOUTS = {
"test_articulation.py": 200,
"test_deformable_object.py": 200,
"test_rigid_object_collection.py": 200,
"test_environments.py": 1850, # This test runs through all the environments for 100 steps each
"test_environment_determinism.py": 200, # This test runs through many the environments for 100 steps each
"test_factory_environments.py": 300, # This test runs through Factory environments for 100 steps each
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment