Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
2fa2cc0
Initial commit for gear assembly sim to real
ashwinvkNV Nov 19, 2025
a01d7f6
remove redundant joint_pos and joint_vel get
ashwinvkNV Nov 19, 2025
fa00654
add all ros parameters and more comments to explain
ashwinvkNV Nov 20, 2025
1b4c05e
Merge branch 'isaac-sim:main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Nov 21, 2025
cc64f6a
add troubleshotting and higher env training
ashwinvkNV Nov 24, 2025
d5e8e43
fixes for comments
ashwinvkNV Nov 24, 2025
5318fe3
use class variables
ashwinvkNV Nov 25, 2025
33212ce
precompute gear randomization indices
ashwinvkNV Nov 25, 2025
4461af3
reduce friction values
ashwinvkNV Nov 26, 2025
5058375
Merge branch 'isaac-sim:main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Nov 26, 2025
035130c
move rsl_rl config to seperate PR
ashwinvkNV Nov 26, 2025
1aa4c96
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 8, 2025
08ed4fb
Use the default usd for the 2f 85 gripper
ashwinvkNV Dec 8, 2025
03767bf
Merge branch 'ashwinvk/deploy_gear_assembly' of github.com:ashwinvkNV…
ashwinvkNV Dec 8, 2025
30ce9fe
move to aws assets and remove commented
ashwinvkNV Dec 10, 2025
e4ec700
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 10, 2025
afd8e96
remove tf_combine usage and unnecessary inheritance
ashwinvkNV Dec 11, 2025
2202d76
Merge branch 'ashwinvk/deploy_gear_assembly' of github.com:ashwinvkNV…
ashwinvkNV Dec 11, 2025
cf5696a
add comment for positive w and change stand name
ashwinvkNV Dec 11, 2025
21d42b3
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 12, 2025
5f1f7a8
move noise model to mdp
ashwinvkNV Dec 12, 2025
dd8736a
formatting fixes
ashwinvkNV Dec 12, 2025
0547fd1
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 16, 2025
bf2541d
add changelogs
ashwinvkNV Dec 16, 2025
f22450b
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 17, 2025
fae5a9e
fixe tests
ashwinvkNV Dec 18, 2025
1c05be7
Merge branch 'ashwinvk/deploy_gear_assembly' of github.com:ashwinvkNV…
ashwinvkNV Dec 18, 2025
56a9618
remove additional finger intial states
ashwinvkNV Dec 18, 2025
d726578
Update source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py
ashwinvkNV Dec 18, 2025
6ff8412
fixes for comments
ashwinvkNV Dec 18, 2025
61c7062
Merge branch 'ashwinvk/deploy_gear_assembly' of github.com:ashwinvkNV…
ashwinvkNV Dec 18, 2025
7abef6c
change to camel case
ashwinvkNV Dec 18, 2025
f5299fe
Merge branch 'main' into ashwinvk/deploy_gear_assembly
ashwinvkNV Dec 19, 2025
96e8911
add links to papers
ashwinvkNV Dec 22, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.

Large diffs are not rendered by default.

1 change: 1 addition & 0 deletions docs/source/policy_deployment/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,3 +10,4 @@ Below, you’ll find detailed examples of various policies for training and depl

00_hover/hover_policy
01_io_descriptors/io_descriptors_101
02_gear_assembly/gear_assembly_policy
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

* :obj:`UR10_CFG`: The UR10 arm without a gripper.
* :obj:`UR10E_ROBOTIQ_GRIPPER_CFG`: The UR10E arm with Robotiq_2f_140 gripper.
* :obj:`UR10e_ROBOTIQ_2F_85_CFG`: The UR10E arm with Robotiq 2F-85 gripper.

Reference: https://github.com/ros-industrial/universal_robot
"""
Expand Down Expand Up @@ -162,4 +163,44 @@
armature=0.0,
)


UR10e_ROBOTIQ_2F_85_CFG = UR10e_CFG.copy()
"""Configuration of UR-10E arm with Robotiq_2f_140 gripper."""
UR10e_ROBOTIQ_2F_85_CFG.spawn.variants = {"Gripper": "Robotiq_2f_85"}
UR10e_ROBOTIQ_2F_85_CFG.spawn.rigid_props.disable_gravity = True
UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos["finger_joint"] = 0.0
UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos[".*_inner_finger_joint"] = 0.0
UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos[".*_inner_finger_knuckle_joint"] = 0.0
UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos[".*_outer_.*_joint"] = 0.0
# the major actuator joint for gripper
UR10e_ROBOTIQ_2F_85_CFG.actuators["gripper_drive"] = ImplicitActuatorCfg(
joint_names_expr=["finger_joint"], # "right_outer_knuckle_joint" is its mimic joint
effort_limit_sim=10.0,
velocity_limit_sim=1.0,
stiffness=11.25,
damping=0.1,
friction=0.0,
armature=0.0,
)
# enable the gripper to grasp in a parallel manner
UR10e_ROBOTIQ_2F_85_CFG.actuators["gripper_finger"] = ImplicitActuatorCfg(
joint_names_expr=[".*_inner_finger_joint"],
effort_limit_sim=1.0,
velocity_limit_sim=1.0,
stiffness=0.2,
damping=0.001,
friction=0.0,
armature=0.0,
)
# set PD to zero for passive joints in close-loop gripper
UR10e_ROBOTIQ_2F_85_CFG.actuators["gripper_passive"] = ImplicitActuatorCfg(
joint_names_expr=[".*_inner_finger_knuckle_joint", "right_outer_knuckle_joint"],
effort_limit_sim=1.0,
velocity_limit_sim=1.0,
stiffness=0.0,
damping=0.0,
friction=0.0,
armature=0.0,
)

"""Configuration of UR-10E arm with Robotiq 2F-85 gripper."""
2 changes: 1 addition & 1 deletion source/isaaclab_tasks/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.11.10"
version = "0.11.12"

# Description
title = "Isaac Lab Environments"
Expand Down
9 changes: 9 additions & 0 deletions source/isaaclab_tasks/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,15 @@
Changelog
---------

0.11.12 (2025-12-16)
~~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added ``Isaac-Deploy-GearAssembly`` environments.


0.11.11 (2025-12-16)
~~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Copyright (c) 2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Assemble 3 gears into a base."""
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Copyright (c) 2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configurations for arm-based gear assembly environments."""

# We leave this file empty since we don't want to expose any configs in this package directly.
# We still need this file to import the "config" module in the parent package.
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
# Copyright (c) 2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##


# UR10e with 2F-140 gripper
gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F140-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:UR10e2F140GearAssemblyEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UR10GearAssemblyRNNPPORunnerCfg",
},
)

gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F140-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:UR10e2F140GearAssemblyEnvCfg_PLAY",
},
)

# UR10e with 2F-85 gripper
gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F85-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:UR10e2F85GearAssemblyEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UR10GearAssemblyRNNPPORunnerCfg",
},
)

gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F85-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:UR10e2F85GearAssemblyEnvCfg_PLAY",
},
)

# UR10e with 2F-140 gripper - ROS Inference
gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F140-ROS-Inference-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.ros_inference_env_cfg:UR10e2F140GearAssemblyROSInferenceEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UR10GearAssemblyRNNPPORunnerCfg",
},
)

# UR10e with 2F-85 gripper - ROS Inference
gym.register(
id="Isaac-Deploy-GearAssembly-UR10e-2F85-ROS-Inference-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.ros_inference_env_cfg:UR10e2F85GearAssemblyROSInferenceEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UR10GearAssemblyRNNPPORunnerCfg",
},
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Copyright (c) 2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab.utils import configclass

from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticRecurrentCfg, RslRlPpoAlgorithmCfg


@configclass
class UR10GearAssemblyRNNPPORunnerCfg(RslRlOnPolicyRunnerCfg):
num_steps_per_env = 512
max_iterations = 1500
save_interval = 50
experiment_name = "gear_assembly_ur10e"
clip_actions = 1.0
resume = False
obs_groups = {
"policy": ["policy"],
"critic": ["critic"],
}
policy = RslRlPpoActorCriticRecurrentCfg(
state_dependent_std=True,
init_noise_std=1.0,
actor_obs_normalization=True,
critic_obs_normalization=True,
actor_hidden_dims=[256, 128, 64],
critic_hidden_dims=[256, 128, 64],
noise_std_type="log",
activation="elu",
rnn_type="lstm",
rnn_hidden_dim=256,
rnn_num_layers=2,
)
algorithm = RslRlPpoAlgorithmCfg(
value_loss_coef=1.0,
use_clipped_value_loss=True,
clip_param=0.2,
entropy_coef=0.0,
num_learning_epochs=8,
num_mini_batches=16,
learning_rate=5.0e-4,
schedule="adaptive",
gamma=0.99,
lam=0.95,
desired_kl=0.008,
max_grad_norm=1.0,
)
Loading
Loading