Skip to content

Conversation

@mpgussert
Copy link
Collaborator

No description provided.

@mpgussert mpgussert requested a review from Mayankm96 as a code owner October 29, 2025 18:24
@github-actions github-actions bot added the isaac-lab Related to Isaac Lab team label Oct 29, 2025
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR introduces a new RL environment for training a UR10 robot equipped with a surface gripper (suction-based) to perform cube lifting tasks. The implementation follows IsaacLab's existing pattern of creating robot-specific variants of base manipulation environments, similar to how Franka and UR10 configurations exist for other tasks. The key changes include: (1) extending the base lift environment configuration to support surface gripper actions alongside traditional joint-based grippers via a union type, (2) creating a complete configuration package under lift/config/ur10_SG/ with environment setup, PPO training hyperparameters, and Gym registration, and (3) configuring the surface gripper with vacuum force limits and binary open/close commands that reflect the on/off nature of suction mechanisms rather than continuous finger positions. The implementation maintains backward compatibility with existing gripper configurations while enabling this new gripper modality.

Important Files Changed

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py 5/5 Extended gripper action type to union supporting both binary joint and surface gripper actions
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/init.py 2/5 Created Gym environment registration with incorrect entry point path "isaaclab.envs" instead of "omni.isaac.lab.envs"
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/joint_pos_env_cfg.py 3/5 Defined UR10 surface gripper environment configuration with surface gripper setup, binary actions, and frame tracking
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/skrl_ppo_cfg.yaml 4/5 Added skrl PPO training configuration with standard hyperparameters but notably low timesteps (36000) for testing
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/init.py 3/5 Created empty initialization file that may prevent proper agent configuration imports

Confidence score: 2/5

  • This PR has critical issues that will prevent it from functioning and requires significant revision before merging
  • Score lowered due to: (1) incorrect entry point path in environment registration that will cause import failures, (2) empty agents __init__.py that may break configuration loading, (3) potential asset name mismatches between scene configuration and action references, (4) missing multi-framework support (only skrl provided, no rsl_rl/rl_games/sb3), (5) debug visualization enabled in production code, and (6) unused import statement
  • Pay close attention to ur10_SG/__init__.py (incorrect entry point), ur10_SG/joint_pos_env_cfg.py (asset name references and debug viz), and agents/__init__.py (missing imports for agent configs)

Sequence Diagram

sequenceDiagram
    participant User
    participant Gymnasium
    participant ManagerBasedRLEnv
    participant UR10SGCubeLiftEnvCfg
    participant Scene
    participant Robot
    participant SurfaceGripper
    participant Object
    participant MDP

    User->>Gymnasium: "gym.make('Isaac-Lift-Cube-UR10SG-v0')"
    Gymnasium->>ManagerBasedRLEnv: "Create environment instance"
    ManagerBasedRLEnv->>UR10SGCubeLiftEnvCfg: "Load configuration"
    UR10SGCubeLiftEnvCfg->>Scene: "Setup ObjectTableSceneCfg"
    Scene->>Robot: "Spawn UR10_SHORT_SUCTION_CFG at {ENV_REGEX_NS}/Robot"
    Scene->>SurfaceGripper: "Create SurfaceGripperCfg at Robot/ee_link/SurfaceGripper"
    SurfaceGripper-->>Scene: "Configure max_grip_distance=0.05, force_limits=5000.0"
    Scene->>Object: "Spawn DexCube at [0.5, 0, 0.055]"
    Scene->>Scene: "Setup FrameTransformer for ee_frame tracking"
    UR10SGCubeLiftEnvCfg->>MDP: "Configure actions (JointPositionAction, SurfaceGripperBinaryAction)"
    UR10SGCubeLiftEnvCfg->>MDP: "Configure observations (joint_pos, joint_vel, object_position)"
    UR10SGCubeLiftEnvCfg->>MDP: "Configure rewards (reaching, lifting, tracking)"
    UR10SGCubeLiftEnvCfg-->>ManagerBasedRLEnv: "Environment configured"
    ManagerBasedRLEnv-->>User: "Environment ready"
    
    User->>ManagerBasedRLEnv: "reset()"
    ManagerBasedRLEnv->>MDP: "reset_scene_to_default"
    ManagerBasedRLEnv->>MDP: "reset_object_position (uniform random)"
    ManagerBasedRLEnv->>MDP: "Generate object_pose command"
    ManagerBasedRLEnv-->>User: "Return observations"
    
    loop Training Loop
        User->>ManagerBasedRLEnv: "step(action)"
        ManagerBasedRLEnv->>MDP: "arm_action (JointPositionAction, scale=0.5)"
        MDP->>Robot: "Apply joint positions to .*_joint"
        ManagerBasedRLEnv->>MDP: "gripper_action (SurfaceGripperBinaryAction)"
        alt Close gripper (action=1.0)
            MDP->>SurfaceGripper: "close_command"
            SurfaceGripper->>Object: "Attempt grip within max_grip_distance"
        else Open gripper (action=-1.0)
            MDP->>SurfaceGripper: "open_command"
            SurfaceGripper->>Object: "Release object"
        end
        ManagerBasedRLEnv->>MDP: "Compute observations (joint states, object position)"
        ManagerBasedRLEnv->>MDP: "Compute rewards (object_ee_distance, object_is_lifted, object_goal_distance)"
        ManagerBasedRLEnv->>MDP: "Check terminations (time_out, object_dropping)"
        ManagerBasedRLEnv-->>User: "Return (obs, reward, done, info)"
    end
Loading

Additional Comments (1)

  1. source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/__init__.py, line 1-5 (link)

    logic: The agents module is empty and missing required imports and exports. Based on the RAG context showing similar files (e.g., ur_10/agents/init.py for reach tasks), this file should expose agent configurations. Without these exports, the RL agent configs (like skrl_ppo_cfg.yaml in this directory) cannot be imported by the parent environment registration. Should this file expose the agent configuration modules, or is this intentionally left empty as a placeholder for future development?

5 files reviewed, 5 comments

Edit Code Review Agent Settings | Greptile

#
# SPDX-License-Identifier: BSD-3-Clause
import gymnasium as gym
import os
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: os is imported but never used in this file


gym.register(
id="Isaac-Lift-Cube-UR10SG-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: entry point should be omni.isaac.lab.envs:ManagerBasedRLEnv to match other environments in the codebase (see RAG sources for Franka and UR10 configs)

Comment on lines 18 to 26
gym.register(
id="Isaac-Lift-Cube-UR10SG-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:UR10SGCubeLiftEnvCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml",
},
disable_env_checker=True,
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: missing additional RL framework cfg_entry_points (rsl_rl_cfg_entry_point, rl_games_cfg_entry_point, sb3_cfg_entry_point) that are typically included in other lift environments. Are you planning to support only skrl for this environment, or should other RL frameworks be configurable too?


self.scene.ee_frame = FrameTransformerCfg(
prim_path="{ENV_REGEX_NS}/Robot/base_link",
debug_vis=True,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: debug visualization is enabled for production code - consider setting debug_vis=False by default and only enabling it in PLAY config or via environment variable

@github-actions github-actions bot added the asset New asset feature or request label Oct 29, 2025
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

Modified the initial pose for the UR10 with long suction gripper by changing wrist_2_joint from 1.5707 to -1.5707 radians (flipping from +90° to -90°).

  • Changed wrist_2_joint initial position to align with UR10e configuration pattern
  • This affects the starting orientation of the end effector for the surface gripper task
  • The change impacts UR10_LONG_SUCTION_CFG and, by inheritance, UR10_SHORT_SUCTION_CFG

Confidence Score: 4/5

  • This PR is safe to merge with minimal risk - it's a simple configuration adjustment
  • The change is straightforward (single joint angle modification), aligns with existing UR10e configuration patterns, and is clearly documented in the commit message. However, score is 4 rather than 5 because: (1) there's no explicit justification for why this specific pose is better for the surface gripper task, and (2) this may affect existing environments that depend on this configuration
  • No files require special attention - the change is isolated and minimal

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py 4/5 Changed wrist_2_joint initial position from 1.5707 to -1.5707 for UR10_LONG_SUCTION_CFG, aligning with UR10e configuration

Sequence Diagram

sequenceDiagram
    participant Dev as Developer
    participant Config as UR10_LONG_SUCTION_CFG
    participant Robot as UR10 Robot
    participant Env as RL Environment

    Dev->>Config: Modify wrist_2_joint initial pose
    Note over Config: Change from 1.5707 to -1.5707
    Config->>Robot: Apply initial joint positions
    Note over Robot: Robot initializes with new pose<br/>wrist_2 rotated -90° instead of +90°
    Robot->>Env: Robot ready in adjusted pose
    Note over Env: Surface gripper task can begin<br/>with corrected initial orientation
Loading

1 file reviewed, no comments

Edit Code Review Agent Settings | Greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR adds a new RL environment for the UR10 robot with surface gripper to perform cube lifting tasks. The implementation includes:

  • Two environment variants using short and long suction grippers with corresponding configurations
  • Proper integration with the existing lift task framework by extending LiftEnvCfg and adding SurfaceGripperBinaryActionCfg support
  • Complete RL framework support with PPO configurations for RSL-RL, RL Games, Stable-Baselines3, and SKRL
  • Modified initial pose for UR10's wrist_2_joint to better accommodate surface gripper orientation
  • Surface gripper configuration with appropriate force limits and grip distance parameters

Key Issues:

  • Missing PLAY environment registrations needed for policy evaluation (Isaac-Lift-Cube-UR10SG-Short-Play-v0 and Isaac-Lift-Cube-UR10SG-Long-Play-v0)
  • Unused os import in __init__.py
  • Debug visualization enabled by default in production code (debug_vis=True)
  • Modified UR10 wrist pose could affect existing environments using UR10_LONG_SUCTION_CFG

Confidence Score: 3/5

  • This PR is mostly safe but requires attention to missing PLAY environments and potential breaking changes to existing UR10 configurations
  • Score of 3/5 reflects: (1) missing critical PLAY environment registrations that are standard across similar environments, (2) modified robot initial pose in shared configuration could break existing environments, (3) minor style issues with unused imports and debug visualization enabled. The core implementation is solid and follows established patterns, but the missing PLAY environments and shared config modification need to be addressed before merging.
  • Pay close attention to __init__.py (missing PLAY registrations) and universal_robots.py (shared config modification that could affect other environments)

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/init.py 3/5 Adds gym environment registrations for UR10 surface gripper lift task; missing PLAY environment variants and has unused import
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/joint_pos_env_cfg.py 4/5 Implements UR10 surface gripper environment configurations for short and long suction variants; has debug visualization enabled by default
source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py 4/5 Modified initial wrist_2_joint pose from 1.5707 to -1.5707 for UR10_LONG_SUCTION_CFG; changes robot's initial configuration

Sequence Diagram

sequenceDiagram
    participant User
    participant GymEnv as Gym Environment
    participant UR10SGEnvCfg as UR10SGCubeLiftEnvCfg
    participant LiftEnvCfg as LiftEnvCfg (Parent)
    participant Robot as UR10_SHORT/LONG_SUCTION
    participant SurfaceGripper as SurfaceGripperCfg
    participant RLAgent as RL Agent (RSL-RL/RL Games/SB3/SKRL)

    User->>GymEnv: gym.make("Isaac-Lift-Cube-UR10SG-Short-v0")
    GymEnv->>UR10SGEnvCfg: Initialize environment config
    UR10SGEnvCfg->>LiftEnvCfg: Call super().__post_init__()
    LiftEnvCfg-->>UR10SGEnvCfg: Base config initialized
    
    UR10SGEnvCfg->>Robot: Setup UR10_SHORT_SUCTION_CFG
    Robot-->>UR10SGEnvCfg: Robot configured with updated wrist_2_joint pose
    
    UR10SGEnvCfg->>SurfaceGripper: Configure SurfaceGripperCfg
    Note over SurfaceGripper: max_grip_distance: 0.05<br/>force_limits: 5000.0
    SurfaceGripper-->>UR10SGEnvCfg: Gripper ready
    
    UR10SGEnvCfg->>UR10SGEnvCfg: Configure actions
    Note over UR10SGEnvCfg: arm_action: JointPositionActionCfg<br/>gripper_action: SurfaceGripperBinaryActionCfg
    
    UR10SGEnvCfg->>UR10SGEnvCfg: Setup FrameTransformer with debug_vis=True
    UR10SGEnvCfg-->>GymEnv: Environment ready
    
    User->>RLAgent: Train with selected framework
    RLAgent->>GymEnv: Reset environment
    GymEnv-->>RLAgent: Initial observations
    
    loop Training Steps
        RLAgent->>GymEnv: Step(arm_action, gripper_action)
        GymEnv->>Robot: Apply joint positions (scaled by 0.5)
        GymEnv->>SurfaceGripper: Apply binary grip command
        Note over SurfaceGripper: -1.0 = open<br/>1.0 = close
        GymEnv-->>RLAgent: Observations, rewards, done
    end
Loading

5 files reviewed, 2 comments

Edit Code Review Agent Settings | Greptile

"sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml",
},
disable_env_checker=True,
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: missing PLAY environment registrations (Isaac-Lift-Cube-UR10SG-Short-Play-v0 and Isaac-Lift-Cube-UR10SG-Long-Play-v0) - these are needed for running trained policies in evaluation mode. See Isaac-Lift-Cube-Franka-Play-v0 registration in franka config for reference

"elbow_joint": 1.5707,
"wrist_1_joint": -1.5707,
"wrist_2_joint": 1.5707,
"wrist_2_joint": -1.5707,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: changed wrist_2_joint from 1.5707 to -1.5707 (90° rotation). Check that this new pose is correct for the surface gripper orientation and doesn't cause collisions or unexpected behavior in existing environments using UR10_LONG_SUCTION_CFG

…xamanination, the file is called PPO but the algorithm is A2C. not sure what's going on so i removed it until clarified
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

Removed rl_games_ppo_cfg.yaml configuration file due to confusion between PPO naming and A2C algorithm implementation. However, the deletion creates a critical breaking change as __init__.py still references the deleted file in both environment registrations (lines 25 and 38).

Key Issues:

  • Environment registration will fail when users try to instantiate Isaac-Lift-Cube-UR10SG-Short-v0 or Isaac-Lift-Cube-UR10SG-Long-v0 with rl_games backend
  • The rl_games_cfg_entry_point parameter in both gym.register() calls points to the now-deleted config file
  • Author's concern about PPO vs A2C naming is valid - Franka's config has the same issue (file named "ppo" but uses algo.name: a2c_continuous)

Recommended Fix:
Either remove the rl_games_cfg_entry_point parameter from both environment registrations in __init__.py, or restore the file until the PPO/A2C naming confusion is resolved upstream.

Confidence Score: 0/5

  • This PR introduces a critical breaking change that will cause runtime failures when users try to create the UR10SG lift environments
  • The deletion breaks environment registration by creating dangling references in __init__.py. Any attempt to instantiate the environments will fail with a file-not-found error. This is a blocking issue that must be fixed before merge.
  • source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/__init__.py requires immediate attention to remove or update the rl_games_cfg_entry_point references

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/rl_games_ppo_cfg.yaml 0/5 Deleted rl_games config file but __init__.py still references it, breaking environment registration

Sequence Diagram

sequenceDiagram
    participant User
    participant GymRegistry
    participant UR10SG_Init as __init__.py
    participant RLGames as rl_games_ppo_cfg.yaml
    participant Environment as ManagerBasedRLEnv

    User->>GymRegistry: gym.make("Isaac-Lift-Cube-UR10SG-Short-v0")
    GymRegistry->>UR10SG_Init: Read registration config
    UR10SG_Init->>UR10SG_Init: Load entry points
    Note over UR10SG_Init: rl_games_cfg_entry_point references<br/>agents:rl_games_ppo_cfg.yaml
    UR10SG_Init--xRLGames: File not found (DELETED)
    Note over RLGames: File was deleted in this commit<br/>due to PPO/A2C naming confusion
    RLGames--xUR10SG_Init: Error: Missing config file
    UR10SG_Init--xGymRegistry: Registration fails
    GymRegistry--xUser: Environment creation fails
Loading

Additional Comments (1)

  1. source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/rl_games_ppo_cfg.yaml, line 1-84 (link)

    logic: deleting this file breaks the environment registrations in __init__.py (lines 25 and 38) which still reference rl_games_cfg_entry_point. Either remove the rl_games_cfg_entry_point parameter from both gym registrations, or keep this file until clarification on the PPO vs A2C issue

1 file reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR adds a new RL environment configuration for the UR10 robot with a surface gripper (SG) for the lift task. The implementation follows established patterns from other lift environments (Franka, UR10 with other grippers).

Key Changes

  • New environment configuration at joint_pos_env_cfg.py with four config classes: base config, PLAY config, and long/short suction variants
  • Surface gripper configuration with appropriate force limits (5000N shear/coaxial) and grip distance (0.05m)
  • Joint position control for the arm and binary action for the surface gripper
  • Frame transformer setup with correct offset (0.1585m) matching other UR10 configurations
  • Modified initial pose in universal_robots.py for wrist_2_joint from 1.5707 to -1.5707 (180° rotation)

Issues Addressed

The PR addresses previously identified issues from comments (not duplicating those here per instructions), and the configuration is structurally sound with proper inheritance and consistent patterns.

Confidence Score: 4/5

  • This PR is reasonably safe to merge after addressing previously identified issues with the init.py file
  • The configuration follows established patterns from other lift environments and uses consistent values (offsets, force limits, etc.) with similar UR10 configurations. The wrist_2_joint angle change appears intentional for surface gripper orientation. Main concerns are debug_vis=True in production code (line 80) and issues already flagged in init.py by previous comments. No critical logical errors in the core configuration.
  • Pay attention to __init__.py for the issues already flagged (unused import, missing PLAY registrations, RL framework configs). The joint_pos_env_cfg.py has debug_vis enabled which should be reviewed.

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/joint_pos_env_cfg.py 4/5 New configuration for UR10 with surface gripper for lift task; uses consistent patterns with other lift environments; debug_vis enabled on line 80
source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py 4/5 Changed wrist_2_joint initial position from 1.5707 to -1.5707 (180° rotation) for surface gripper orientation

Sequence Diagram

sequenceDiagram
    participant Env as ManagerBasedRLEnv
    participant Robot as UR10_SHORT/LONG_SUCTION
    participant SG as SurfaceGripper
    participant Object as DexCube
    participant EE as FrameTransformer
    
    Env->>Robot: Initialize with joint positions
    Env->>SG: Create surface gripper at ee_link
    Note over SG: max_grip_distance=0.05<br/>shear/coaxial_force=5000N
    Env->>Object: Spawn cube at [0.5, 0, 0.055]
    Env->>EE: Setup frame tracking (base_link → ee_link)
    Note over EE: offset=[0.1585, 0.0, 0.0]
    
    loop Training Episode
        Env->>Robot: Apply JointPositionAction (scale=0.5)
        Note over Robot: Control all .*_joint
        Env->>SG: Apply SurfaceGripperBinaryAction
        alt close_command (1.0)
            SG->>Object: Attempt grip within 0.05m
            Object-->>SG: Object attached
        else open_command (-1.0)
            SG->>Object: Release grip
            Object-->>SG: Object detached
        end
        EE->>Env: Report ee_frame transform
        Env->>Env: Compute observations & rewards
        Env->>Env: Check termination conditions
    end
Loading

1 file reviewed, no comments

Edit Code Review Agent Settings | Greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR adds a new RL environment for the UR10 robot with surface gripper support for the cube lifting task. The implementation creates two environment variants (short and long suction configurations) with corresponding PLAY configs for evaluation.

Key changes:

  • Added new ur10_SG config directory with environment registrations, agent configurations (rsl_rl, skrl, sb3), and joint position control configs
  • Modified lift_env_cfg.py to support SurfaceGripperBinaryActionCfg as an alternative gripper action type
  • Updated UR10_LONG_SUCTION_CFG wrist_2_joint initial pose from 1.5707 to -1.5707 radians (180° rotation change)

Issues identified:

  • Missing PLAY environment gym registrations (Isaac-Lift-Cube-UR10SG-Short-Play-v0 and Isaac-Lift-Cube-UR10SG-Long-Play-v0) needed for running trained policies
  • Unused os import in __init__.py
  • Debug visualization enabled by default in production code (debug_vis=True on line 80 of joint_pos_env_cfg.py)
  • The wrist_2_joint pose change affects the shared UR10_LONG_SUCTION_CFG used by other environments - verify this doesn't break existing setups

Confidence Score: 3/5

  • This PR has several non-critical issues that should be addressed before merging
  • The core implementation appears solid with proper surface gripper integration and multi-framework RL support. However, missing PLAY environment registrations prevents policy evaluation, unused imports reduce code quality, and debug visualization enabled in production wastes resources. The wrist_2_joint pose change to a shared config could potentially affect other environments using UR10_LONG_SUCTION_CFG.
  • Pay close attention to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/__init__.py (missing PLAY registrations) and source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py (verify pose change doesn't break existing environments)

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/init.py 3/5 Registers two new gym environments for UR10 with surface gripper. Missing PLAY environment registrations and has unused os import.
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/joint_pos_env_cfg.py 4/5 Implements UR10 surface gripper lift environment configs. Has debug visualization enabled by default (line 80).
source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py 4/5 Changed wrist_2_joint initial pose from 1.5707 to -1.5707 radians for UR10_LONG_SUCTION_CFG.
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py 5/5 Added SurfaceGripperBinaryActionCfg as alternative gripper action type to support surface grippers.

Sequence Diagram

sequenceDiagram
    participant User
    participant Gym
    participant UR10SGEnv as UR10SG Environment
    participant Robot as UR10 Robot
    participant SurfaceGripper
    participant Cube
    
    User->>Gym: Register Isaac-Lift-Cube-UR10SG-Short-v0
    Gym->>UR10SGEnv: Initialize ManagerBasedRLEnv
    UR10SGEnv->>Robot: Load UR10_SHORT_SUCTION_CFG
    UR10SGEnv->>SurfaceGripper: Configure SurfaceGripperCfg
    Note over SurfaceGripper: max_grip_distance=0.05<br/>force_limits=5000.0
    UR10SGEnv->>Cube: Spawn DexCube at [0.5, 0, 0.055]
    
    User->>UR10SGEnv: Reset environment
    UR10SGEnv->>Robot: Set joint positions (wrist_2=-1.5707)
    UR10SGEnv->>UR10SGEnv: Initialize frame transformer
    Note over UR10SGEnv: debug_vis=True (enabled)
    
    loop Training Loop
        User->>UR10SGEnv: Step with action
        UR10SGEnv->>Robot: Apply JointPositionAction (scale=0.5)
        UR10SGEnv->>SurfaceGripper: Apply SurfaceGripperBinaryAction
        alt Gripper Close (action=1.0)
            SurfaceGripper->>Cube: Attach if within 0.05m
        else Gripper Open (action=-1.0)
            SurfaceGripper->>Cube: Detach
        end
        Robot->>UR10SGEnv: Return state
        UR10SGEnv->>User: Return observation, reward, done
    end
Loading

1 file reviewed, no comments

Edit Code Review Agent Settings | Greptile

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR adds a new RL environment for the UR10 robot with surface gripper for cube lifting tasks. It registers two training environments (Isaac-Lift-Cube-UR10SG-Short-v0 and Isaac-Lift-Cube-UR10SG-Long-v0) with support for multiple RL frameworks (rsl_rl, skrl, sb3, rl_games).

Key Changes:

  • Adds environment configuration with SurfaceGripperCfg for the UR10 robot end effector
  • Implements SurfaceGripperBinaryActionCfg for gripper control (open/close commands)
  • Updates base LiftEnvCfg to support surface gripper actions alongside joint actions
  • Provides agent configurations for all major RL frameworks (rsl_rl, skrl, sb3, rl_games)
  • Modifies UR10_LONG_SUCTION_CFG wrist_2_joint initial pose from 1.5707 to -1.5707

Critical Issues:

  • The rl_games_ppo_cfg.yaml file has a critical algorithm mismatch - it's named PPO but implements A2C (algo: a2c_continuous, model: continuous_a2c_logstd). This is the exact issue that caused rl_games support to be removed in commit fab2d12
  • Missing PLAY environment registrations needed for evaluation mode

Confidence Score: 1/5

  • This PR has a critical algorithm mismatch in rl_games config that will cause incorrect training behavior
  • Score reflects the critical issue where rl_games configuration file is named PPO but implements A2C algorithm. This exact mismatch was identified in commit fab2d12 and caused removal of rl_games support. The inconsistency between the file name, algorithm configuration (lines 15, 18), and config flag (line 53: ppo: True) will lead to unexpected training behavior. Additionally, missing PLAY environment registrations prevent proper evaluation workflows. These issues must be resolved before merging.
  • source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/rl_games_ppo_cfg.yaml requires immediate attention due to algorithm mismatch. source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/__init__.py needs PLAY environment registrations added

Important Files Changed

File Analysis

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/init.py 2/5 Registers UR10 surface gripper lift environments but missing PLAY variants for evaluation and has unused import
source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/ur10_SG/agents/rl_games_ppo_cfg.yaml 0/5 Critical algorithm mismatch - file named PPO but implements A2C algorithm (same issue that caused removal in fab2d12)

Sequence Diagram

sequenceDiagram
    participant User
    participant Gym
    participant UR10SGEnv as UR10SG Environment
    participant Robot as UR10 Robot
    participant SurfaceGripper as Surface Gripper
    participant Cube as Object (Cube)
    participant RLAgent as RL Agent (PPO/A2C)
    
    User->>Gym: Register Isaac-Lift-Cube-UR10SG-Short/Long-v0
    Gym->>UR10SGEnv: Create environment with joint_pos_env_cfg
    UR10SGEnv->>Robot: Initialize UR10_SHORT/LONG_SUCTION_CFG
    UR10SGEnv->>SurfaceGripper: Configure surface gripper (max_grip_distance=0.05)
    UR10SGEnv->>Cube: Spawn cube at [0.5, 0, 0.055]
    
    User->>RLAgent: Train with rsl_rl/skrl/sb3/rl_games
    loop Training Episodes
        RLAgent->>UR10SGEnv: Get observations
        UR10SGEnv->>Robot: Query joint positions
        UR10SGEnv->>SurfaceGripper: Query gripper state
        UR10SGEnv->>Cube: Query cube pose
        UR10SGEnv-->>RLAgent: Return state
        
        RLAgent->>UR10SGEnv: Send action (joint_pos + gripper)
        UR10SGEnv->>Robot: Apply JointPositionAction
        UR10SGEnv->>SurfaceGripper: Apply SurfaceGripperBinaryAction
        
        alt Gripper closes
            SurfaceGripper->>Cube: Attach if within max_grip_distance
        else Gripper opens
            SurfaceGripper->>Cube: Detach
        end
        
        UR10SGEnv->>RLAgent: Return reward + done
    end
Loading

2 files reviewed, 3 comments

Edit Code Review Agent Settings | Greptile

clip_actions: 100.0

algo:
name: a2c_continuous
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: file named rl_games_ppo_cfg.yaml but algo is a2c_continuous not PPO. Line 53 says ppo: True but lines 15 and 18 configure A2C. This mismatch was noted in commit fab2d12 and caused the removal of rl_games support. Either fix the algorithm to use actual PPO or remove rl_games support until clarified

#
# SPDX-License-Identifier: BSD-3-Clause
import gymnasium as gym
import os
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: os is imported but never used

Suggested change
import os
import gymnasium as gym

"sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml",
},
disable_env_checker=True,
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: missing PLAY environment registrations (e.g., Isaac-Lift-Cube-UR10SG-Short-Play-v0 and Isaac-Lift-Cube-UR10SG-Long-Play-v0). These are needed for running trained policies in evaluation mode. See Isaac-Lift-Cube-Franka-Play-v0 registration at franka/__init__.py:32

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

asset New asset feature or request isaac-lab Related to Isaac Lab team

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant