-
Notifications
You must be signed in to change notification settings - Fork 2.8k
Description
Hi,
I'm working on a custom lift task in Isaac Lab using the UR10e robotic arm equipped with the Robotiq 2F-140 gripper. Below, I summarize the steps I've followed so far and describe the issue I’m currently encountering.
Steps Completed
1. USD Asset Setup
- Created a custom USD using Isaac Sim.
- Added the UR10e arm and Robotiq 2F-140 gripper using existing Isaac Sim assets.
- Enabled the required variants:
physics,sensors, andgripper.
Preview of the setup:
2. Custom Configuration
Robot Configuration
We created a custom ArticulationCfg for the UR10e with the Robotiq 2F-140:
UR10_ROBOTIQ_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"/workspace/isaaclab/source/isaaclab_assets/isaaclab_assets/robots/ur10e_2f140.usd",
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
),
activate_contact_sensors=False,
),
init_state=ArticulationCfg.InitialStateCfg(
joint_pos={
# Arm joints
"shoulder_pan_joint": 0.0,
"shoulder_lift_joint": -1.0,
"elbow_joint": 1.0,
"wrist_1_joint": 0.0,
"wrist_2_joint": 0.0,
"wrist_3_joint": 0.0,
# Gripper joints (optional initial positions)
"left_inner_finger_joint": 0.0,
"right_inner_finger_joint": 0.0,
"left_outer_finger_joint": 0.0,
"right_outer_finger_joint": 0.0,
"finger_joint": 0.0,
"right_outer_knuckle_joint": 0.0,
"right_inner_finger_pad_joint": 0.0,
"left_inner_finger_pad_joint": 0.0
},
),
actuators={
"arm": ImplicitActuatorCfg(
joint_names_expr=[
"shoulder_pan_joint",
"shoulder_lift_joint",
"elbow_joint",
"wrist_1_joint",
"wrist_2_joint",
"wrist_3_joint",
],
velocity_limit_sim=20.0,
effort_limit_sim=87.0,
stiffness=800.0,
damping=40.0,
),
"gripper": ImplicitActuatorCfg(
joint_names_expr=[
"left_inner_finger_joint",
"right_inner_finger_joint",
"left_outer_finger_joint",
"right_outer_finger_joint",
"finger_joint",
"right_outer_knuckle_joint",
"right_inner_finger_pad_joint",
"left_inner_finger_pad_joint"
],
velocity_limit_sim=20.0,
effort_limit_sim=20.0,
stiffness=500.0,
damping=0.0,
),
},
)
"""Configuration of UR10e arm with Robotiq 2F-140 gripper using implicit actuator models."""
Lift Environment Configuration
from isaaclab.assets import RigidObjectCfg
from isaaclab.sensors import FrameTransformerCfg
from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg
from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg
from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
from isaaclab_tasks.manager_based.manipulation.lift import mdp
from isaaclab_tasks.manager_based.manipulation.lift.lift_env_cfg import LiftEnvCfg
from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip
from isaaclab_assets import UR10_ROBOTIQ_CFG # devi verificare il path corretto
@configclass
class UR10eCubeLiftEnvCfg(LiftEnvCfg):
def __post_init__(self):
super().__post_init__()
# Set UR10e as robot with correct prim path
self.scene.robot = UR10_ROBOTIQ_CFG.replace(prim_path="{ENV_REGEX_NS}/ur10e")
# Set actions for UR10e
self.actions.arm_action = mdp.JointPositionActionCfg(
asset_name="robot",
joint_names=[
"shoulder_pan_joint",
"shoulder_lift_joint",
"elbow_joint",
"wrist_1_joint",
"wrist_2_joint",
"wrist_3_joint"
],
scale=0.5,
use_default_offset=True
)
self.actions.gripper_action = mdp.BinaryJointPositionActionCfg(
asset_name="robot",
joint_names=[
"left_inner_finger_joint",
"right_inner_finger_joint",
"left_outer_finger_joint",
"right_outer_finger_joint",
"finger_joint",
"right_outer_knuckle_joint",
"right_inner_finger_pad_joint",
"left_inner_finger_pad_joint"
],
open_command_expr={
"left_inner_finger_joint": 0.04,
"right_inner_finger_joint": 0.04,
"left_outer_finger_joint": 0.04,
"right_outer_finger_joint": 0.04,
"finger_joint": 0.04,
"right_outer_knuckle_joint": 0.04,
"right_inner_finger_pad_joint": 0.04,
"left_inner_finger_pad_joint": 0.04
},
close_command_expr={
"left_inner_finger_joint": 0.0,
"right_inner_finger_joint": 0.0,
"left_outer_finger_joint": 0.0,
"right_outer_finger_joint": 0.0,
"finger_joint": 0.0,
"right_outer_knuckle_joint": 0.0,
"right_inner_finger_pad_joint": 0.0,
"left_inner_finger_pad_joint": 0.0
}
)
# End effector body name (da verificare nel tuo USD)
self.commands.object_pose.body_name = "robotiq_base_link"
# Cube as object to lift
""" self.scene.object = RigidObjectCfg(
prim_path="{ENV_REGEX_NS}/Object",
init_state=RigidObjectCfg.InitialStateCfg(pos=[0.5, 0, 0.055], rot=[1, 0, 0, 0]),
spawn=UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd",
scale=(0.8, 0.8, 0.8),
rigid_props=RigidBodyPropertiesCfg(
solver_position_iteration_count=16,
solver_velocity_iteration_count=1,
max_angular_velocity=1000.0,
max_linear_velocity=1000.0,
max_depenetration_velocity=5.0,
disable_gravity=False,
),
),
) """
# Frame marker configuration
marker_cfg = FRAME_MARKER_CFG.copy()
marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
marker_cfg.prim_path = "/Visuals/FrameTransformer"
self.scene.ee_frame = FrameTransformerCfg(
prim_path="{ENV_REGEX_NS}/ur10e/base_link",
debug_vis=True,
visualizer_cfg=marker_cfg,
target_frames=[
FrameTransformerCfg.FrameCfg(
prim_path="{ENV_REGEX_NS}/ur10e/gripper/robotiq_base_link",
name="end_effector",
offset=OffsetCfg(
pos=[0.0, 0.0, 0.1034],
),
)
],
)
@configclass
class UR10eCubeLiftEnvCfg_PLAY(FrankaCubeLiftEnvCfg):
def __post_init__(self):
super().__post_init__()
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
self.observations.policy.enable_corruption = False
❗ Current Issue
We adapted the default Franka Lift task from Isaac Lab to work with the UR10e + Robotiq 2F-140 setup by modifying the robot and environment configurations as shown above.
We trained the policy using the rsl_rl library with 4096 parallel environments. While the simulation runs smoothly, the robot consistently fails to complete the lift task. In particular:
-
The reward consistently trends toward large negative values during training.
-
The training loss rapidly increases and appears to diverge toward infinity, with no sign of convergence.
Screenshot:
If you’ve worked with similar setups or have tips for:
- Stabilizing the gripper control,
- Improving reward shaping or reward thresholds,
- Validating mimic joint or articulation configs,
...any suggestions would be much appreciated!
Thanks in advance for your support!