Isaac Lab Teleoperation & Data Collection: Controlling the AgileX NERO 7-DoF Robotic Arm

0. Preface

In this tutorial, we walk through the step-by-step implementation of keyboard teleoperation and demonstration data collection for the AgileX NERO (7-DoF) and PiPER robotic arms within NVIDIA Isaac Lab.

By the end of this guide, you will be able to control the robotic arm in a simulated environment to perform a block-stacking (Pick and Place) task, collect human demonstration data (HDF5), and replay the dataset for imitation learning pipeline verification.

:rocket: Key Capabilities Supported

  • Multimodal Teleoperation: Direct keyboard control for end-effector SE(3) pose alignment.

  • Pick-and-Place (Stacking) Task: Multi-block stacking simulation environment.

  • Demonstration Collection: Seamless HDF5 data logging compatible with Robomimic.

  • Trajectory Replay: Instant validation of collected human demonstrations.

  • Cross-Hardware Support: Out-of-the-box support for AgileX NERO (7-DoF) and PiPER (6-DoF) arms.

:package:Project Open-Source Repo

1.Environment & Hardware Configuration

1.1 Generate the Unified URDF File

To import the NERO arm into Omniverse, we must first merge its separate XACRO description files into a single, clean URDF.

Navigate to your local repository directory:

source/agx_teleop/agx_description/agx_arm_urdf/nero

Merge nero_description.urdf, nero_with_gripper_flange_description.xacro, and nero_with_gripper_description.xacro into a single file named nero_gripper.urdf. Ensure all visual/collision mesh paths pointing to local ROS packages are resolved to relative directory paths (e.g., ../meshes/).

Here is the complete nero_gripper.urdf:


<?xml version="1.0" ?>

<robot name="agx_arm">

  <link name="world"/>

  <joint name="world_to_base_link" type="fixed">

      <parent link="world"/>

      <child link="base_link"/>

      <origin rpy="0 0 3.14" xyz="0 0 0"/>

  </joint>

  <link name="base_link">

    <inertial>

      <origin rpy="0 0 0" xyz="-0.00319465997 -0.00005467608 0.04321758463"/>

      <mass value="1.06458435"/>

      <inertia ixx="0.00102659855152" ixy="0.00000186219753" ixz="-0.00000295298037" iyy="0.00114399299508" iyz="-0.00000078763492" izz="0.00090872933022"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/base_link.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/base_link.stl"/>

      </geometry>

    </collision>

  </link>

  <link name="link1">

    <inertial>

      <origin rpy="0 0 0" xyz="-0.00076810578 -0.00005718031 -0.00686372765"/>

      <mass value="0.76710504"/>

      <inertia ixx="0.00066689512233" ixy="0.00000273938306" ixz="0.00001463284987" iyy="0.00054501235592" iyz="0.00000183168344" izz="0.00051509465737"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link1.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link1.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint1" type="revolute">

    <origin rpy="0 0 0" xyz="0 0 0.138"/>

    <parent link="base_link"/>

    <child link="link1"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-2.70526" upper="2.70526" velocity="5"/>

  </joint>

  <link name="link2">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00079686657 -0.07890325930 0.00111849422"/>

      <mass value="0.69381908"/>

      <inertia ixx="0.00201093857656" ixy="-0.00002399426785" ixz="-0.00000072824714" iyy="0.00063544232555" iyz="0.00005831284343" izz="0.00181943989593"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link2.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link2.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint2" type="revolute">

    <origin rpy="1.5707963  3.1415926 0" xyz="0 0 0"/>

    <parent link="link1"/>

    <child link="link2"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-1.74" upper="1.74" velocity="5"/>

  </joint>

  <link name="link3">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00014513363 -0.00121378766 -0.04861136795"/>

      <mass value="0.67246544"/>

      <inertia ixx="0.00343229961910" ixy="-0.00000026976739" ixz="0.00000305078107" iyy="0.00338662526897" iyz="-0.00003550220027" izz="0.00028853579710"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link3.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link3.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint3" type="revolute">

    <origin rpy="-1.5707963  0 3.1415926926" xyz="0 -0.31 0"/>

    <parent link="link2"/>

    <child link="link3"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-2.75" upper="2.75" velocity="5"/>

  </joint>

  <link name="link4">

    <inertial>

      <origin rpy="0 0 0" xyz="-0.00031334623 -0.05675192422 0.00076056133"/>

      <mass value="0.48451414"/>

      <inertia ixx="0.00050386693505" ixy="-0.00000529675237" ixz="0.00000006134740" iyy="0.00023502068202" iyz="0.00001815932566" izz="0.00040149523118"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link4.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link4.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint4" type="revolute">

    <origin rpy="-1.5707963  0 3.1415926926" xyz="0 0 0"/>

    <parent link="link3"/>

    <child link="link4"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-1.01" upper="2.14" velocity="5"/>

  </joint>

  <link name="link5">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00265591357 0.00201195753 -0.11620855434"/>

      <mass value="0.58368405"/>

      <inertia ixx="0.00089537686723" ixy="0.00000648218232" ixz="-0.00001463346849" iyy="0.00085866122972" iyz="-0.00004035185637" izz="0.00021774946532"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link5.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link5.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint5" type="revolute">

    <origin rpy="1.5707963  -1.5707963  0" xyz="0 -0.27001 0"/>

    <parent link="link4"/>

    <child link="link5"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-2.75" upper="2.75" velocity="5"/>

  </joint>

  <link name="link6">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00009501505 0.00107831174 -0.00019110990"/>

      <mass value="0.3140406"/>

      <inertia ixx="0.00006027211661" ixy="-0.00000024650903" ixz="0.00000015701294" iyy="0.00004699514792" iyz="0.00000004170875" izz="0.00005756771792"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link6.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link6.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint6" type="revolute">

    <origin rpy="1.5707963  -1.5707963  0" xyz="0 0 0"/>

    <parent link="link5"/>

    <child link="link6"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-0.73" upper="0.95" velocity="5"/>

  </joint>

  <link name="link7">

    <inertial>

      <origin rpy="0 0 0" xyz="-0.00014000 -0.00010000 -0.00275000"/>

      <mass value="0.000001"/>

      <inertia ixx="1.1000000000000001e-07" ixy="0" ixz="0" iyy="1.1000000000000001e-07" iyz="0" izz="1.9999999999999999e-07"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/link7.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/link7.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="joint7" type="revolute">

    <origin rpy="1.5707963 0 0" xyz="0 -0.0235 0"/>

    <parent link="link6"/>

    <child link="link7"/>

    <axis xyz="0 0 1"/>

    <limit effort="100" lower="-1.5707963" upper="1.5707963" velocity="5"/>

  </joint>

  <link name="gripper_flange">

    <inertial>

      <origin rpy="0 0 0" xyz="0.0 0.0 -0.00032"/>

      <mass value="0.04771096"/>

      <inertia ixx="2.697e-05" ixy="0" ixz="0" iyy="4.311e-05" iyz="0" izz="2.479e-05"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/gripper_flange.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/gripper_flange.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="gripper_flange_joint" type="fixed">

    <origin rpy="-1.5708 0 -1.5708" xyz="0.032 0 -0.0235"/>

    <parent link="link7"/>

    <child link="gripper_flange"/>

  </joint>

  <link name="gripper_base">

    <inertial>

      <origin rpy="0 0 0" xyz="-0.000183807162235591 8.05033155577911E-05 0.0321436689908876"/>

      <mass value="0.45"/>

      <inertia ixx="0.00092934" ixy="0.00000034" ixz="-0.00000738" iyy="0.00071447" iyz="0.00000005" izz="0.00039442"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/gripper_base.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/gripper_base.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="gripper_base_joint" type="fixed">

    <origin rpy="0 0 0" xyz="0 0 0.0055"/>

    <parent link="gripper_flange"/>

    <child link="gripper_base"/>

  </joint>

  <link name="gripper_link1">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00065123185041968 -0.0491929869131989 0.00972258769184025"/>

      <mass value="0.025"/>

      <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/gripper_link1.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/gripper_link1.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="gripper_joint1" type="prismatic">

    <origin rpy="1.5707963 0 3.1415926" xyz="0 0 0.1358"/>

    <parent link="gripper_base"/>

    <child link="gripper_link1"/>

    <axis xyz="0 0 1"/>

    <limit effort="10" lower="0" upper="0.05" velocity="3"/>

  </joint>

  <link name="gripper_link2">

    <inertial>

      <origin rpy="0 0 0" xyz="0.00065123185041968 -0.0491929869131989 0.00972258769184025"/>

      <mass value="0.025"/>

      <inertia ixx="0.00007371" ixy="-0.00000113" ixz="0.00000021" iyy="0.00000781" iyz="-0.00001372" izz="0.0000747"/>

    </inertial>

    <visual>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/dae/gripper_link2.dae"/>

      </geometry>

    </visual>

    <collision>

      <origin rpy="0 0 0" xyz="0 0 0"/>

      <geometry>

        <mesh filename="../meshes/gripper_link2.stl"/>

      </geometry>

    </collision>

  </link>

  <joint name="gripper_joint2" type="prismatic">

    <origin rpy="1.5707963 0 0" xyz="0 0 0.1358"/>

    <parent link="gripper_base"/>

    <child link="gripper_link2"/>

    <axis xyz="0 0 -1"/>

    <limit effort="10" lower="-0.05" upper="0" velocity="3"/>

  </joint>

</robot>

1.2 Compile URDF to USD Format

Convert the generated URDF into an NVIDIA USD (Universal Scene Description) file using Isaac Lab’s built-in exporter utility:


python ../IsaacLab/scripts/tools/convert_urdf.py 

  /home/agilex/isaac-cosmos/agx_teleop/source/agx_teleop/agx_description/agx_arm_urdf/nero/urdf/nero_gripper.urdf 

  /home/agilex/isaac-cosmos/agx_teleop/source/agx_teleop/agx_description/agx_arm_urdf/nero/usd/nero.usd 

  --fix-base 

1.3 Create the Asset Configuration File

Create assets/nero.py to define the simulated joints, limits, PD controller gains, and stiffness/damping coefficients.


import isaaclab.sim as sim_utils

from isaaclab.actuators import ImplicitActuatorCfg

from isaaclab.assets.articulation import ArticulationCfg

from agx_teleop.assets import AGX_TELEOP_DESCRIPTION_DIR



NERO_GRIPPER_CFG = ArticulationCfg(

    spawn=sim_utils.UsdFileCfg(

        usd_path=f"{AGX_TELEOP_DESCRIPTION_DIR}/agx_arm_urdf/nero/usd/nero.usd",

        rigid_props=sim_utils.RigidBodyPropertiesCfg(

            disable_gravity=False,

            max_depenetration_velocity=5.0,

        ),

        articulation_props=sim_utils.ArticulationRootPropertiesCfg(

            enabled_self_collisions=False, solver_position_iteration_count=8, solver_velocity_iteration_count=0

        ),

    ),

    init_state=ArticulationCfg.InitialStateCfg(

        rot=(1.0, 0.0, 0.0, 0.0),

        joint_pos={

            "joint1": 0.0,

            "joint2": 0.0,

            "joint3": 0.0,

            "joint4": 1.22,

            "joint5": 0.0,

            "joint6": 0.0,

            "joint7": 1.31,

            "gripper_joint1": 0.05,

            "gripper_joint2": -0.05

        },

        joint_vel={".*": 0.0},

    ),

    actuators={

        "arm": ImplicitActuatorCfg(

            joint_names_expr=["joint.*"],

            effort_limit=25.0, 

            velocity_limit=1.5,

            stiffness={

                "joint1": 200.0, 

                "joint2": 170.0,

                "joint3": 120.0,

                "joint4": 80.0,

                "joint5": 50.0,

                "joint6": 20.0,

                "joint7": 10.0

            },

            damping={

                "joint1": 100.0,

                "joint2": 60.0,

                "joint3": 70.0,

                "joint4": 24.0,

                "joint5": 20.0,

                "joint6": 10.0,

                "joint7": 5,

            },

        ),

        "gripper": ImplicitActuatorCfg(

            joint_names_expr=\["gripper_joint1","gripper_joint2"\],

            effort_limit_sim=22,

            velocity_limit_sim=1.5,

            stiffness=800.0,

            damping=20.0,

        ),

    },

    soft_joint_pos_limit_factor=0.9,

)



NERO_GRIPPER_HIGH_PD_CFG = NERO_GRIPPER_CFG.copy()

NERO_GRIPPER_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True

2.Task Environment Configuration

2.1 Configure Directory Tree Structure

Setup your task configurations under the standard Isaac Lab layout:

Adapted from the official Isaac Lab stacking task implementation: isaaclab/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack


cd agx_teleop

mkdir -p source/agx_teleop/agx_teleop/tasks/manager_based/manipulation/stack/config/nero/agents/robomimic

Create the required task files:


cd source/agx_teleop/agx_teleop/tasks/manager_based/

touch   manipulation/stack/config/nero/__init__.py 

        manipulation/stack/config/nero/agents/__init__.py 

        manipulation/stack/config/nero/agents/robomimic/bc_rnn_low_dim.json 

        manipulation/stack/config/nero/nero_stack_ik_rel_env_cfg.py 

        manipulation/stack/config/nero/nero_stack_joint_pos_env_cfg.py

3. Implement Configurations

3.1 bc_rnn_low_dim.json (Robomimic Behavior Cloning Profile)

This file defines policy network structures (LSTM with Gaussian Mixture Models) for downstream imitation learning. Copy your target JSON config as-is without extra modifications:


{

    "algo_name": "bc",

    "experiment": {

        "name": "bc_rnn_low_dim_franka_stack",

        "validate": false,

        "logging": { "terminal_output_to_txt": true, "log_tb": true },

        "save": {

            "enabled": true,

            "every_n_seconds": null,

            "every_n_epochs": 100,

            "epochs": \[\],

            "on_best_validation": false,

            "on_best_rollout_return": false,

            "on_best_rollout_success_rate": true

        },

        "epoch_every_n_steps": 100,

        "env": null,

        "additional_envs": null,

        "render": false,

        "render_video": false,

        "rollout": { "enabled": false }

    },

    "train": {

        "data": null,

        "num_data_workers": 4,

        "hdf5_cache_mode": "all",

        "hdf5_use_swmr": true,

        "hdf5_normalize_obs": false,

        "hdf5_filter_key": null,

        "hdf5_validation_filter_key": null,

        "seq_length": 10,

        "dataset_keys": [ "actions" ],

        "goal_mode": null,

        "cuda": true,

        "batch_size": 100,

        "num_epochs": 2000,

        "seed": 101

    },

    "algo": {

        "optim_params": {

            "policy": {

                "optimizer_type": "adam",

                "learning_rate": {

                    "initial": 0.001,

                    "decay_factor": 0.1,

                    "epoch_schedule": [],

                    "scheduler_type": "multistep"

                },

                "regularization": { "L2": 0.0 }

            }

        },

        "loss": { "l2_weight": 1.0, "l1_weight": 0.0, "cos_weight": 0.0 },

        "actor_layer_dims": [],

        "gmm": {

            "enabled": true,

            "num_modes": 5,

            "min_std": 0.0001,

            "std_activation": "softplus",

            "low_noise_eval": true

        },

        "rnn": {

            "enabled": true,

            "horizon": 10,

            "hidden_dim": 400,

            "rnn_type": "LSTM",

            "num_layers": 2,

            "open_loop": false,

            "kwargs": { "bidirectional": false }

        }

    },

    "observation": {

        "modalities": {

            "obs": {

                "low_dim": [ "eef_pos", "eef_quat", "gripper_pos", "object" ],

                "rgb": [], "depth": [], "scan": []

            }

        }

    }

}

3.2 nero_stack_joint_pos_env_cfg.py (Joint Position Environment)

Sets up state configurations, randomizing object spawn spaces and assigning physical bounds to NERO.


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

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 agx_teleop.tasks.manager_based.manipulation.stack import mdp

from agx_teleop.tasks.manager_based.manipulation.stack.mdp import piper_stack_events

from agx_teleop.tasks.manager_based.manipulation.stack.stack_env_cfg import StackEnvCfg



from isaaclab.markers.config import FRAME_MARKER_CFG  

from agx_teleop.assets.nero import NERO_GRIPPER_CFG  



@configclass

class EventCfg:

    init_nero_arm_pose = EventTerm(

        func=piper_stack_events.set_default_joint_pose,

        mode="reset",

        params={

            "default_pose": [0.0, 0.0, 0.0, 1.22, 0.0, 0.0, 1.31, 0.05, -0.05],   

        },

    )



    randomize_nero_joint_state = EventTerm(

        func=piper_stack_events.randomize_joint_by_gaussian_offset,

        mode="reset",

        params={

            "mean": 0.0,

            "std": 0.02,

            "asset_cfg": SceneEntityCfg("robot"),

        },

    )



    randomize_cube_positions = EventTerm(

        func=piper_stack_events.randomize_object_pose,

        mode="reset",

        params={

            "pose_range": {"x": (0.3, 0.5), "y": (-0.10, 0.10), "z": (0.0203, 0.0203), "yaw": (-1.0, 1, 0)},

            "min_separation": 0.12,

            "asset_cfgs": [SceneEntityCfg("cube_1"), SceneEntityCfg("cube_2"), SceneEntityCfg("cube_3")],

        },

    )



@configclass

class NeroCubeStackEnvCfg(StackEnvCfg):

    def __post_init__(self):

        super().__post_init__()



        self.events = EventCfg()

        self.scene.robot = NERO_GRIPPER_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")

        self.scene.robot.spawn.semantic_tags = [("class", "robot")]

        self.scene.table.spawn.semantic_tags = [("class", "table")]

        self.scene.plane.semantic_tags = [("class", "ground")]



        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=["gripper_joint.*"],

            open_command_expr={"gripper_joint1": 0.05, "gripper_joint2": -0.05},

            close_command_expr={"gripper_joint1": 0.0, "gripper_joint2": 0.0},

        )

        self.gripper_joint_names = ["gripper_joint.*"]

        self.gripper_open_val = [0.05, -0.05]

        self.gripper_threshold = 0.005



        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,

        )



        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=(1.0, 1.0, 1.0),

                rigid_props=cube_properties,

                semantic_tags=[("class", "cube_1")],

            ),

        )

        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=(1.0, 1.0, 1.0),

                rigid_props=cube_properties,

                semantic_tags=[("class", "cube_2")],

            ),

        )

        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=(1.0, 1.0, 1.0),

                rigid_props=cube_properties,

                semantic_tags=[("class", "cube_3")],

            ),

        )



        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}/Robot/world",

            debug_vis=False,

            visualizer_cfg=marker_cfg,

            target_frames=[

                FrameTransformerCfg.FrameCfg(

                    prim_path="{ENV_REGEX_NS}/Robot/gripper_base",

                    name="end_effector",

                    offset=OffsetCfg(pos=[0.0, 0.0, 0.125\]),

                ),

                FrameTransformerCfg.FrameCfg(

                    prim_path="{ENV_REGEX_NS}/Robot/gripper_link1",

                    name="tool_rightfinger",

                    offset=OffsetCfg(pos=(0.0, 0.0, 0.0)),

                ),

                FrameTransformerCfg.FrameCfg(

                    prim_path="{ENV_REGEX_NS}/Robot/gripper_link2",

                    name="tool_leftfinger",

                    offset=OffsetCfg(pos=(0.0, 0.0, 0.0)),

                ),

            ],

        )

3.3 Teleoperation, Data Collection & Replay

3.3.1 stack/config/nero/nero_stack_ik_rel_env_cfg.py

Copy the corresponding Isaac Lab code and modify the following:

  • Update imports and naming

  • Modify the end-effector offset

Complete code for nero_stack_ik_rel_env_cfg.py:


# Copyright (c) 2022-2026, 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 DeviceBase, DevicesCfg

from isaaclab.devices.keyboard import Se3KeyboardCfg

from isaaclab.devices.openxr.openxr_device import OpenXRDeviceCfg

from isaaclab.devices.openxr.retargeters.manipulator.gripper_retargeter import GripperRetargeterCfg

from isaaclab.devices.openxr.retargeters.manipulator.se3_rel_retargeter import Se3RelRetargeterCfg

from isaaclab.envs.mdp.actions.actions_cfg import DifferentialInverseKinematicsActionCfg

from isaaclab.managers import SceneEntityCfg

from isaaclab.managers import TerminationTermCfg as DoneTerm

from isaaclab.utils import configclass



from agx_teleop.tasks.manager_based.manipulation.stack.stack_env_cfg import mdp



from . import nero_stack_joint_pos_env_cfg



##

# Pre-defined configs

##

from agx_teleop.assets.nero import NERO_GRIPPER_HIGH_PD_CFG  # isort: skip




@configclass

class NeroCubeStackEnvCfg(nero_stack_joint_pos_env_cfg.NeroCubeStackEnvCfg):

    def __post_init__(self):

        # post init of parent

        super().__post_init__()



        # Set Nero as robot

        # We switch here to a stiffer PD controller for IK tracking to be better.

        self.scene.robot = NERO_GRIPPER_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")



        # Set actions for the specific robot type (nero)

        self.actions.arm_action = DifferentialInverseKinematicsActionCfg(

            asset_name="robot",

            joint_names=["joint.*"],

            body_name="gripper_base",

            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.125]),

        )



        self.teleop_devices = DevicesCfg(

            devices={

                "handtracking": OpenXRDeviceCfg(

                    retargeters=[

                        Se3RelRetargeterCfg(

                            bound_hand=DeviceBase.TrackingTarget.HAND_RIGHT,

                            zero_out_xy_rotation=True,

                            use_wrist_rotation=False,

                            use_wrist_position=True,

                            delta_pos_scale_factor=10.0,

                            delta_rot_scale_factor=10.0,

                            sim_device=self.sim.device,

                        ),

                        GripperRetargeterCfg(

                            bound_hand=DeviceBase.TrackingTarget.HAND_RIGHT, sim_device=self.sim.device

                        ),

                    ],

                    sim_device=self.sim.device,

                    xr_cfg=self.xr,

                ),

                "keyboard": Se3KeyboardCfg(

                    pos_sensitivity=0.05,

                    rot_sensitivity=0.05,

                    sim_device=self.sim.device,

                ),

            }

        )




@configclass

class NeroCubeStackRedGreenEnvCfg(NeroCubeStackEnvCfg):

    def __post_init__(self):

        \# post init of parent

        super().__post_init__()



        self.terminations.success = DoneTerm(

            func=mdp.cubes_stacked,

            params={"cube_1_cfg": SceneEntityCfg("cube_2"), "cube_2_cfg": SceneEntityCfg("cube_3"), "cube_3_cfg": None},

        )




@configclass

class NeroCubeStackRedGreenBlueEnvCfg(NeroCubeStackEnvCfg):

    def __post_init__(self):

        # post init of parent

        super().__post_init__()



        self.terminations.success = DoneTerm(

            func=mdp.cubes_stacked,

            params={

                "cube_1_cfg": SceneEntityCfg("cube_2"),

                "cube_2_cfg": SceneEntityCfg("cube_3"),

                "cube_3_cfg": SceneEntityCfg("cube_1"),

            },

        )




@configclass

class NeroCubeStackBlueGreenEnvCfg(NeroCubeStackEnvCfg):

    def __post_init__(self):

        # post init of parent

        super().__post_init__()



        self.terminations.success = DoneTerm(

            func=mdp.cubes_stacked,

            params={"cube_1_cfg": SceneEntityCfg("cube_1"), "cube_2_cfg": SceneEntityCfg("cube_3"), "cube_3_cfg": None},

        )




@configclass

class NeroCubeStackBlueGreenRedEnvCfg(NeroCubeStackEnvCfg):

    def __post_init__(self):

        # post init of parent

        super().__post_init__()



        self.terminations.success = DoneTerm(

            func=mdp.cubes_stacked,

            params={

                "cube_1_cfg": SceneEntityCfg("cube_1"),

                "cube_2_cfg": SceneEntityCfg("cube_3"),

                "cube_3_cfg": SceneEntityCfg("cube_2"),

            },

        )



3.3.2 stack/config/nero/init.py**


# Copyright (c) 2022-2026, 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 isaaclab_tasks.manager_based.manipulation.stack.config.franka import agents

from agx_teleop.tasks.manager_based.manipulation.stack.config.nero import agents



\##

# Register Gym environments.

##



gym.register(

    id="Isaac-Stack-Cube-Nero-IK-Rel-v0",

    entry_point="isaaclab.envs:ManagerBasedRLEnv",

    kwargs={

        "env_cfg_entry_point": f"{__name__}.nero_stack_ik_rel_env_cfg:NeroCubeStackEnvCfg",

        "robomimic_bc_cfg_entry_point": f"{agents.__name__}:robomimic/bc_rnn_low_dim.json",

    },

    disable_env_checker=True,

)

4. Collect Demonstration Data via Teleoperation


# First, create a dataset directory

mkdir -p datasets

# Record demonstrations via teleoperation.

# This example uses keyboard teleoperation.
# Available devices: spacemouse, keyboard, handtracking

python scripts/tools/record_demos.py 

    --task Isaac-Stack-Cube-Nero-IK-Rel-v0 

    --device cpu --teleop_device keyboard 

    --dataset_file ./datasets/nero_dataset.hdf5 

    --num_demos 10


# Replay the recorded demonstrations

python scripts/tools/replay_demos.py 

    --task Isaac-Stack-Cube-Nero-IK-Rel-v0 

    --device cpu --dataset_file ./datasets/nero_dataset.hdf5

Keyboard teleoperation controls:


Keyboard Controller for SE(3): Se3Keyboard



Reset all commands: R

Toggle gripper (open/close): K



Move arm along x-axis: W/S

Move arm along y-axis: A/D

Move arm along z-axis: Q/E



Rotate arm along x-axis: Z/X

Rotate arm along y-axis: T/G

Rotate arm along z-axis: C/V

FAQ

Q1: How do I adapt this pipeline from the 7-DoF NERO arm to the 6-DoF PiPER arm (or any other custom manipulator)?

To swap the robot asset, you need to update three core configuration files in your task directory:

1.Asset Definition (assets/piper.py): Define the new USD file path, update the default joint positions (joint_pos) to match a 6-DoF configuration, and re-tune the stiffness/damping parameters for the 6 active joints.

2.Action Configuration (piper_stack_joint_pos_env_cfg.py): Modify the joint regular expression to match the PiPER joint names (e.g., changing expression targets from 7 joints to 6). Update the gripper joint names and binary open/close limit values.

3.Differential IK Config (piper_stack_ik_rel_env_cfg.py):Update the body_name parameter to point to the correct end-effector link (e.g., link6 or gripper_base) and adjust the body_offset to match the physical dimension of the PiPER gripper flange.


Q2: The robotic gripper slips or fails to lift the blocks during teleoperation. How do I improve grap stability?

Slipping or unstable grasping in Isaac Lab is usually a physics-tuning issue rather than an algorithmic one. Try the following adjustments:

  • Increase Gripper Stiffness: In your asset configuration (assets/nero.py or piper.py), increase the gripper actuator stiffness (e.g., to 800.0 or 1000.0) and effort_limit to ensure the gripper applies enough physical force.

  • Verify Collision Geometries: Open your converted .usd asset in Isaac Sim and check that the collision meshes for the gripper fingers are set to “Convex Decomposition” (or Simplfied Box) rather than a loose bounding box.

  • Adjust Material Friction: Add a high-friction physics material (e.g., static friction coefficient.


Q3: Are the collected HDF5 datasets directly compatible with popular imitation learning codebases like ACT or Diffusion Policy?

Yes, with minor formatting adjustments. The HDF5 files generated by our record_demos.py script closely follow the standard Robomimic data structure, containing hierarchically organized datasets:

  • data/demo_x/obs/eef_pos & eef_quat (End-effector pose)

  • data/demo_x/obs/joint_values (Joint angles)

  • data/demo_x/actions (User control inputs)

To feed this data into ACT (Action Chunking with Transformers) or Diffusion Policy, you can use Robomimic’s conversion scripts (convert_robomimic_to_numpy.py) or write a simple Python wrapper to map the HDF5 dictionary keys to the observation/action expectations of your specific network.


Q4: The simulation occasionally crashes or the robot “explodes” (joints jitter violently) when starting teleoperation. How do I fix this?

“Exploding” physics usually happen when the control gains (PD) are too aggressive, or the solver parameters are too coarse.

  • Increase Solver Iterations: In your environment configuration, increase the solver iterations on the robot asset:

articulation_props=sim_utils.ArticulationRootPropertiesCfg(

    solver_position_iteration_count=16, # Increase from 8 to 16

    solver_velocity_iteration_count=4    # Increase from 0 to 4

)

  • Disable Self-Collisions: Ensure that adjacent links on the arm do not have overlapping collision meshes by setting enabled_self_collisions=False.

  • Lower Stiffness: If the arm vibrates violently upon contact, slightly lower the joint stiffness in your actuator configuration and add proportional damping (ideal ratio is roughly 10:1 to 20:1 for stiffness to damping).

nero_teleop