Skip to content

[Question] UR3e + Robotiq_2F_140_physics_edit : Pick and Place task #4083

@sandokim

Description

@sandokim

Hello I assembled ur3e + Robotiq_2F_140_physics_edit(ur3e_gripper.zip) and tried to perfrom pick and place task with it.

I configured manager-based workflow for it and sucessfully launch isaaclab to do demo with it. But the problem here is when I move my ur3e+gripper to pick and place cube in the environment, the gripper is rotating further when the gripper grap the cube.

Is there any recommendation for solving this problem? I upload the code and usd file that I used!

C:/IsaacLab/source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py

# 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


"""Configuration for the Universal Robots.

The following configuration parameters are available:

* :obj:`UR10_CFG`: The UR10 arm without a gripper.
* :obj:`UR10E_ROBOTIQ_GRIPPER_CFG`: The UR10E arm with Robotiq_2f_140 gripper.
* :obj:`UR3e_CFG`: The UR3e arm without a gripper.
* :obj:`UR3e_GRIPPER_CFG`: The UR3e arm with Robotiq_2F_140_physics_edit gripper.
* :obj:`UR3e_SHORT_SUCTION_CFG`: The UR3e arm with short suction gripper.

Reference: https://github.com/ros-industrial/universal_robot
"""

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

##
# Configuration
##

UR10_CFG = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/UniversalRobots/UR10/ur10_instanceable.usd",
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            disable_gravity=False,
            max_depenetration_velocity=5.0,
        ),
        activate_contact_sensors=False,
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        joint_pos={
            "shoulder_pan_joint": 0.0,
            "shoulder_lift_joint": -1.712,
            "elbow_joint": 1.712,
            "wrist_1_joint": 0.0,
            "wrist_2_joint": 0.0,
            "wrist_3_joint": 0.0,
        },
    ),
    actuators={
        "arm": ImplicitActuatorCfg(
            joint_names_expr=[".*"],
            effort_limit_sim=87.0,
            stiffness=800.0,
            damping=40.0,
        ),
    },
)

UR10e_CFG = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/UniversalRobots/ur10e/ur10e.usd",
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            disable_gravity=True,
            max_depenetration_velocity=5.0,
        ),
        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
            enabled_self_collisions=False, solver_position_iteration_count=16, solver_velocity_iteration_count=1
        ),
        activate_contact_sensors=False,
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        joint_pos={
            "shoulder_pan_joint": 3.141592653589793,
            "shoulder_lift_joint": -1.5707963267948966,
            "elbow_joint": 1.5707963267948966,
            "wrist_1_joint": -1.5707963267948966,
            "wrist_2_joint": -1.5707963267948966,
            "wrist_3_joint": 0.0,
        },
        pos=(0.0, 0.0, 0.0),
        rot=(1.0, 0.0, 0.0, 0.0),
    ),
    actuators={
        # 'shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint'
        "shoulder": ImplicitActuatorCfg(
            joint_names_expr=["shoulder_.*"],
            stiffness=1320.0,
            damping=72.6636085,
            friction=0.0,
            armature=0.0,
        ),
        "elbow": ImplicitActuatorCfg(
            joint_names_expr=["elbow_joint"],
            stiffness=600.0,
            damping=34.64101615,
            friction=0.0,
            armature=0.0,
        ),
        "wrist": ImplicitActuatorCfg(
            joint_names_expr=["wrist_.*"],
            stiffness=216.0,
            damping=29.39387691,
            friction=0.0,
            armature=0.0,
        ),
    },
)

"""Configuration of UR-10 arm using implicit actuator models."""

UR10_LONG_SUCTION_CFG = UR10_CFG.copy()
UR10_LONG_SUCTION_CFG.spawn.usd_path = f"{ISAAC_NUCLEUS_DIR}/Robots/UniversalRobots/ur10/ur10.usd"
UR10_LONG_SUCTION_CFG.spawn.variants = {"Gripper": "Long_Suction"}
UR10_LONG_SUCTION_CFG.spawn.rigid_props.disable_gravity = True
UR10_LONG_SUCTION_CFG.init_state.joint_pos = {
    "shoulder_pan_joint": 0.0,
    "shoulder_lift_joint": -1.5707,
    "elbow_joint": 1.5707,
    "wrist_1_joint": -1.5707,
    "wrist_2_joint": 1.5707,
    "wrist_3_joint": 0.0,
}

"""Configuration of UR10 arm with long suction gripper."""

UR10_SHORT_SUCTION_CFG = UR10_LONG_SUCTION_CFG.copy()
UR10_SHORT_SUCTION_CFG.spawn.variants = {"Gripper": "Short_Suction"}

"""Configuration of UR10 arm with short suction gripper."""

UR10e_ROBOTIQ_GRIPPER_CFG = UR10e_CFG.copy()
UR10e_ROBOTIQ_GRIPPER_CFG.spawn.variants = {"Gripper": "Robotiq_2f_140"}
UR10e_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props.disable_gravity = True
UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos["finger_joint"] = 0.0
UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_joint"] = 0.0
UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_pad_joint"] = 0.0
UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_outer_.*_joint"] = 0.0
# the major actuator joint for gripper
UR10e_ROBOTIQ_GRIPPER_CFG.actuators["gripper_drive"] = ImplicitActuatorCfg(
    joint_names_expr=["finger_joint"],
    effort_limit_sim=10.0,
    velocity_limit_sim=1.0,
    stiffness=11.25,
    damping=0.1,
    friction=0.0,
    armature=0.0,
)
# the auxiliary actuator joint for gripper
UR10e_ROBOTIQ_GRIPPER_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,
)
# the passive joints for gripper
UR10e_ROBOTIQ_GRIPPER_CFG.actuators["gripper_passive"] = ImplicitActuatorCfg(
    joint_names_expr=[".*_inner_finger_pad_joint", ".*_outer_finger_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_140 gripper."""

UR3e_CFG = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=r"C:\isaacsim_assets\isaac-sim-assets-robots_and_sensors-5.0.0\Assets\Isaac\5.0\Isaac\Robots\UniversalRobots\ur3e\ur3e_gripper.usd",
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            disable_gravity=True,
            max_depenetration_velocity=5.0,
        ),
        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
            enabled_self_collisions=False, solver_position_iteration_count=64, solver_velocity_iteration_count=16
        ),
        activate_contact_sensors=False,
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        joint_pos={
            "shoulder_pan_joint": 3.141592653589793,
            "shoulder_lift_joint": -1.5707963267948966,
            "elbow_joint": 1.5707963267948966,
            "wrist_1_joint": -1.5707963267948966,
            "wrist_2_joint": -1.5707963267948966,
            "wrist_3_joint": 0.0,
        },
        pos=(0.0, 0.0, 0.0),
        rot=(1.0, 0.0, 0.0, 0.0),
    ),
    actuators={
        # 'shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint'
        "shoulder": ImplicitActuatorCfg(
            joint_names_expr=["shoulder_.*"],
            stiffness=1320.0,
            damping=72.6636085,
            friction=0.0,
            armature=0.0,
        ),
        "elbow": ImplicitActuatorCfg(
            joint_names_expr=["elbow_joint"],
            stiffness=600.0,
            damping=34.64101615,
            friction=0.0,
            armature=0.0,
        ),
        "wrist": ImplicitActuatorCfg(
            joint_names_expr=["wrist_.*"],
            stiffness=216.0,
            damping=29.39387691,
            friction=0.0,
            armature=0.0,
        ),
    },
)

"""Configuration of UR-3e arm using implicit actuator models."""

UR3e_CFG = UR3e_CFG.copy()
UR3e_CFG.spawn.usd_path = r"C:\isaacsim_assets\isaac-sim-assets-robots_and_sensors-5.0.0\Assets\Isaac\5.0\Isaac\Robots\UniversalRobots\ur3e\ur3e_gripper.usd"
UR3e_CFG.spawn.variants = {"Gripper": "None"}
UR3e_CFG.spawn.rigid_props.disable_gravity = True
UR3e_CFG.init_state.joint_pos = {
    "shoulder_pan_joint": 0.0,
    "shoulder_lift_joint": -1.5707,
    "elbow_joint": 1.5707,
    "wrist_1_joint": -1.5707,
    "wrist_2_joint": 1.5707,
    "wrist_3_joint": 0.0,
}

"""Configuration of UR3e arm with Robotiq_2F_140_physics_edit gripper."""

UR3e_ROBOTIQ_GRIPPER_CFG = UR3e_CFG.copy()
UR3e_ROBOTIQ_GRIPPER_CFG.spawn.variants = {"Gripper": "Robotiq_2F_140_physics_edit"}
UR3e_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props.disable_gravity = True
UR3e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos["finger_joint"] = 0.0
UR3e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_joint"] = 0.0
UR3e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_pad_joint"] = 0.0
UR3e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_outer_.*_joint"] = 0.0
# the major actuator joint for gripper
UR3e_ROBOTIQ_GRIPPER_CFG.actuators["gripper_drive"] = ImplicitActuatorCfg(
    joint_names_expr=["finger_joint"],
    effort_limit_sim=10.0,
    velocity_limit_sim=1.0,
    stiffness=11.25,
    damping=0.1,
    friction=0.0,
    armature=0.0,
)
# the auxiliary actuator joint for gripper
UR3e_ROBOTIQ_GRIPPER_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,
)
# the passive joints for gripper
UR3e_ROBOTIQ_GRIPPER_CFG.actuators["gripper_passive"] = ImplicitActuatorCfg(
    joint_names_expr=[".*_inner_finger_pad_joint", ".*_outer_finger_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-3e arm with Robotiq_2F_140_physics_edit gripper."""

C:/Isaaclab/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur3e_gripper/init.py

# 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

import gymnasium as gym

##
# Register Gym environments.
##


##
# Inverse Kinematics - Relative Pose Control
##

gym.register(
    id="Isaac-Stack-Cube-UR3e-IK-Rel-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    kwargs={
        "env_cfg_entry_point": f"{__name__}.stack_ik_rel_env_cfg:UR3eGripperCubeStackEnvCfg",
    },
    disable_env_checker=True,
)

C:/Isaaclabsource/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur3e_gripper/stack_ik_rel_env_cfg.py

# 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.controllers.differential_ik_cfg import DifferentialIKControllerCfg
from isaaclab.devices.device_base import DevicesCfg
from isaaclab.devices.keyboard import Se3KeyboardCfg
from isaaclab.devices.spacemouse import Se3SpaceMouseCfg
from isaaclab.envs.mdp.actions.actions_cfg import DifferentialInverseKinematicsActionCfg
from isaaclab.utils import configclass

from . import stack_joint_pos_env_cfg


@configclass
class UR3eGripperCubeStackEnvCfg(stack_joint_pos_env_cfg.UR3eGripperCubeStackEnvCfg):

    def __post_init__(self):
        super().__post_init__()

        self.actions.arm_action = DifferentialInverseKinematicsActionCfg(
            asset_name="robot",
            joint_names=[".*_joint"],
            body_name="wrist_3_link",
            controller=DifferentialIKControllerCfg(command_type="pose", use_relative_mode=True, ik_method="dls"),
            scale=0.5,
            body_offset=DifferentialInverseKinematicsActionCfg.OffsetCfg(
                pos=(0.0, 0.0, 0.1995), # offset of "2F-140" gripper along z-axis.                                    
                rot=(0.0, -0.7071, 0.0, -0.7071), # set the TCP coords to be looked same direction in provided "Isaac-Stack-Cube-UR10-Long-Suction-IK-Rel-v0" task.
            ),
        )

        self.teleop_devices = DevicesCfg(
            devices={
                "keyboard": Se3KeyboardCfg(
                    pos_sensitivity=0.02,
                    rot_sensitivity=0.05,
                    sim_device=self.sim.device,
                ),
                "spacemouse": Se3SpaceMouseCfg(
                    pos_sensitivity=0.05,
                    rot_sensitivity=0.05,
                    sim_device=self.sim.device,
                ),
            }
        )

C:/Isaaclabsource/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur3e_gripper/stack_joint_pos_env_cfg.py

# 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.assets import RigidObjectCfg
from isaaclab.managers import EventTermCfg as EventTerm
from isaaclab.managers import SceneEntityCfg
from isaaclab.sensors import FrameTransformerCfg
from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg
from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg, MassPropertiesCfg
from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg
from isaaclab.utils import configclass
import isaaclab.utils.math as math_utils
import torch
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR

from isaaclab_tasks.manager_based.manipulation.stack import mdp
from isaaclab_tasks.manager_based.manipulation.stack.mdp import ur3e_stack_events
from isaaclab_tasks.manager_based.manipulation.stack.mdp import franka_stack_events
from isaaclab_tasks.manager_based.manipulation.stack.stack_env_cfg import StackEnvCfg

from isaaclab_assets.robots.universal_robots import (  # isort: skip
    UR3e_ROBOTIQ_GRIPPER_CFG,
)

##
# Pre-defined configs
##
from isaaclab.markers.config import FRAME_MARKER_CFG  # isort: skip


@configclass
class EventCfgUR3eGripper:
    """Configuration for events."""

    init_ur3e_arm_pose = EventTerm(
        func=ur3e_stack_events.set_ur3e_arm_default_joint_pose,
        mode="reset",
        params={
            "default_pose": [0.0, -1.5707, 1.5707, -1.5707, -1.5707, 0.0],
        },
    )
    
    init_ur3e_gripper_pose = EventTerm(
        func=ur3e_stack_events.set_ur3e_gripper_default_joint_pose,
        mode="reset",
        params={
            "default_pose": [0.785],
        },
    )

    # Apply payload of Robotiq 2F-140: mass 2.315 kg, CoM at (0, 0, 0.0714) m in wrist frame
    apply_ur3e_gripper_payload = EventTerm(
        func=ur3e_stack_events.set_ur3e_payload_on_wrist,
        mode="reset",
        params={
            "payload_mass": 2.315,
            "payload_com": [0.0, 0.0, 0.0714],
            "asset_cfg": SceneEntityCfg("robot"),
        },
    )

    randomize_ur3e_joint_state = EventTerm(
        func=ur3e_stack_events.randomize_ur3e_arm_joint_by_gaussian_offset,
        mode="reset",
        params={
            "mean": 0.0,
            "std": 0.02,
            "asset_cfg": SceneEntityCfg("robot"),
        },
    )

    randomize_cube_positions = EventTerm(
        func=franka_stack_events.randomize_object_pose,
        mode="reset",
        params={
            "pose_range": {"x": (0.4, 0.6), "y": (-0.10, 0.10), "z": (0.0203, 0.0203), "yaw": (-1.0, 1.0, 0)},
            "min_separation": 0.1,
            "asset_cfgs": [SceneEntityCfg("cube_1"), SceneEntityCfg("cube_2"), SceneEntityCfg("cube_3")],
        },
    )


@configclass
class UR3eCubeStackEnvCfg(StackEnvCfg):
    cube_properties = 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,
    )
    cube_scale = (1.0, 1.0, 1.0)
    marker_cfg = FRAME_MARKER_CFG.copy()
    marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
    marker_cfg.prim_path = "/Visuals/FrameTransformer"

    def __post_init__(self):
        super().__post_init__()

        self.events = EventCfgUR3eGripper()

        self.actions.arm_action = mdp.JointPositionActionCfg(
            asset_name="robot", joint_names=[".*_joint"], scale=0.5, use_default_offset=True
            )
        self.actions.gripper_action = mdp.BinaryJointPositionActionCfg(
            asset_name="robot",
            joint_names=["finger_joint"],  
            open_command_expr={
                "finger_joint": 0.65,           
            },
            close_command_expr={
                "finger_joint": 0.0,                 
            },
        )
        # Only parallel joints are supported?
        self.gripper_joint_names = ["left_inner_finger_joint", "right_inner_finger_joint"]
        self.gripper_open_val = 0.04
        self.gripper_threshold = 0.005

        # cube mass default: 0.02
        # Set mass to 0 for testing
        cube_mass_props = MassPropertiesCfg(mass=0.02)
        self.scene.cube_1 = RigidObjectCfg(
            prim_path="{ENV_REGEX_NS}/Cube_1",
            init_state=RigidObjectCfg.InitialStateCfg(pos=[0.4, 0.0, 0.0203], rot=[1, 0, 0, 0]),
            spawn=UsdFileCfg(
                usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/blue_block.usd",
                scale=self.cube_scale,
                rigid_props=self.cube_properties,
                mass_props=cube_mass_props,
            ),
        )
        self.scene.cube_2 = RigidObjectCfg(
            prim_path="{ENV_REGEX_NS}/Cube_2",
            init_state=RigidObjectCfg.InitialStateCfg(pos=[0.55, 0.05, 0.0203], rot=[1, 0, 0, 0]),
            spawn=UsdFileCfg(
                usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/red_block.usd",
                scale=self.cube_scale,
                rigid_props=self.cube_properties,
                mass_props=cube_mass_props,
            ),
        )
        self.scene.cube_3 = RigidObjectCfg(
            prim_path="{ENV_REGEX_NS}/Cube_3",
            init_state=RigidObjectCfg.InitialStateCfg(pos=[0.60, -0.1, 0.0203], rot=[1, 0, 0, 0]),
            spawn=UsdFileCfg(
                usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/green_block.usd",
                scale=self.cube_scale,
                rigid_props=self.cube_properties,
                mass_props=cube_mass_props,
            ),
        )

        self.decimation = 5
        self.episode_length_s = 30.0
        # simulation settings
        self.sim.dt = 0.01  # 100Hz
        self.sim.render_interval = 5
    
    
@configclass
class UR3eGripperCubeStackEnvCfg(UR3eCubeStackEnvCfg):

    def __post_init__(self):
        # post init of parent
        super().__post_init__()
        
        # Set events
        self.events = EventCfgUR3eGripper()

        # Set UR3e with Gripper as robot
        self.scene.robot = UR3e_ROBOTIQ_GRIPPER_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")

        self.scene.ee_frame = FrameTransformerCfg(
            prim_path="{ENV_REGEX_NS}/Robot/base_link",
            debug_vis=True,
            visualizer_cfg=self.marker_cfg,
            target_frames=[
                FrameTransformerCfg.FrameCfg(
                    prim_path="{ENV_REGEX_NS}/Robot/wrist_3_link",
                    name="end_effector",
                    offset=OffsetCfg(
                        pos=(0.0, 0.0, 0.1995), # offset of "2F-140" gripper along z-axis.
                        rot=(0.0, -0.7071, 0.0, -0.7071), # set the TCP coords to be looked same direction in provided "Isaac-Stack-Cube-UR10-Long-Suction-IK-Rel-v0" task.
                    ),
                ),
            ],
        )

C:/Isaaclab/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/ur3e_stack_events.py

# 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 __future__ import annotations

import math
import random
import torch
from typing import TYPE_CHECKING

from isaacsim.core.utils.extensions import enable_extension

import isaaclab.utils.math as math_utils
from isaaclab.assets import Articulation, AssetBase
from isaaclab.managers import SceneEntityCfg

if TYPE_CHECKING:
    from isaaclab.envs import ManagerBasedEnv


# Helper constants and functions specific to UR3e arm control
ARM_JOINT_NAMES = [
    "shoulder_pan_joint",
    "shoulder_lift_joint",
    "elbow_joint",
    "wrist_1_joint",
    "wrist_2_joint",
    "wrist_3_joint",
]

GRIPPER_JOINT_NAMES = [
    "finger_joint",
]

def set_ur3e_arm_default_joint_pose(env, env_ids, default_pose, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot")):
    robot = env.scene[asset_cfg.name]
    arm_joint_ids, _ = robot.find_joints(ARM_JOINT_NAMES)
    default_pose_tensor = torch.tensor(default_pose, device=env.device).unsqueeze(0).repeat(len(env_ids), 1)

    # Update only arm joints in the default joint positions
    robot.data.default_joint_pos[env_ids[:, None], arm_joint_ids] = default_pose_tensor
    

def set_ur3e_gripper_default_joint_pose(env, env_ids, default_pose, asset_cfg: SceneEntityCfg = SceneEntityCfg("robot")):
    robot = env.scene[asset_cfg.name]
    gripper_joint_ids, _ = robot.find_joints(GRIPPER_JOINT_NAMES)
    default_pose_tensor = torch.tensor(default_pose, device=env.device).unsqueeze(0).repeat(len(env_ids), 1)

    # Update only gripper joints in the default joint positions
    robot.data.default_joint_pos[env_ids[:, None], gripper_joint_ids] = default_pose_tensor


def randomize_ur3e_arm_joint_by_gaussian_offset(
    env,
    env_ids,
    mean: float,
    std: float,
    asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
    robot = env.scene[asset_cfg.name]
    arm_joint_ids, _ = robot.find_joints(ARM_JOINT_NAMES)

    joint_pos = robot.data.default_joint_pos[env_ids].clone()
    joint_vel = robot.data.default_joint_vel[env_ids].clone()

    noise = math_utils.sample_gaussian(mean, std, (len(env_ids), len(arm_joint_ids)), joint_pos.device)
    joint_pos[:, arm_joint_ids] += noise

    limits = robot.data.soft_joint_pos_limits[env_ids][:, arm_joint_ids, :]
    joint_pos[:, arm_joint_ids] = torch.clamp(joint_pos[:, arm_joint_ids], limits[..., 0], limits[..., 1])

    robot.set_joint_position_target(joint_pos, env_ids=env_ids)
    robot.set_joint_velocity_target(joint_vel, env_ids=env_ids)
    robot.write_joint_state_to_sim(joint_pos, joint_vel, env_ids=env_ids)


def set_ur3e_payload_on_wrist(
    env: "ManagerBasedEnv",
    env_ids,
    payload_mass: float,
    payload_com: list[float],
    asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
    """Apply a payload to the UR3e wrist by updating mass and CoM of the wrist link.

    The combined center of mass is computed as a mass-weighted average of the existing wrist link CoM and
    the payload CoM expressed in the wrist link frame.
    """
    robot: Articulation = env.scene[asset_cfg.name]
    # resolve env ids on CPU (writer APIs accept CPU ids)
    if env_ids is None:
        env_ids = torch.arange(env.scene.num_envs, device="cpu")
    else:
        env_ids = env_ids.cpu()
    # find wrist body index
    wrist_ids, _ = robot.find_bodies(["wrist_3_link"])
    if len(wrist_ids) == 0:
        raise RuntimeError("Could not find 'wrist_3_link' in robot bodies.")
    wrist_id = wrist_ids[0]
    # fetch current masses/CoMs (clone to CPU)
    masses = robot.root_physx_view.get_masses().clone().cpu()
    coms = robot.root_physx_view.get_coms().clone().cpu()
    # payload CoM as tensor (meters)
    payload_com_t = torch.tensor(payload_com, dtype=coms.dtype, device="cpu")
    # apply per selected envs
    m0 = masses[env_ids, wrist_id]
    c0 = coms[env_ids, wrist_id, :3]
    m_new = m0 + payload_mass
    c_new = (m0.unsqueeze(-1) * c0 + payload_mass * payload_com_t.unsqueeze(0)) / m_new.unsqueeze(-1)
    masses[env_ids, wrist_id] = m_new
    coms[env_ids, wrist_id, :3] = c_new
    # write back
    robot.root_physx_view.set_masses(masses, env_ids)
    robot.root_physx_view.set_coms(coms, env_ids)

Image

Image

You can find the result video and discussion on the https://discordapp.com/channels/827959428476174346/1439937737708011590

  • Please note that I ran cursorAI to write set_ur3e_payload_on_wrist function in the code, so it has been fully inspected yet.

  • Isaac Lab Version: 2.2.1

  • Isaac Sim Version: 5.1.0

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions