Manipulator Converted From Mujoco Menagerie Falls Under Gravity Despite High Stiffness and Damping

I am trying to convert the ViperX 300 6DOF arm from the Mujoco menagerie to a USD Articulation object to use for a manipulation task in IsaacLab.

I would expect the arm to stay put under gravity, but the arm falls as soon as gravity is applied to the scene. This occurs regardless of the joint stiffness and damping values (even when I try with high stiffness, for instance). If I set joint positions using set_joint_position_target, the arm will still fall. This is a video of the arm falling when placing it on a ground plane, even with joint positions applied:

Steps to Reproduce

Clone the Mujoco menagerie, and run the convert_mjcf script with

./isaaclab.sh -p source/standalone/tools/convert_mjcf.py \
  ~/Workspace/mujoco_menagerie/trossen_vx300s/vx300s.xml \
  source/extensions/omni.isaac.lab_assets/data/Robots/VX300s/vx300s.usd \
  --import-sites \
  --make-instanceable \
  --fix-base

I was following this tutorial from the IsaacLab documentation.

The arm falls when pressing play (as shown in the above video), even when I set the stiffness to something like 100000.0 and damping to something like 1000.0.

As a workaround, I tried disabling gravity for the arm like so: VIPER_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True.

However, this causes the robot to stay static when running the example standalone/tutorials/05_controllers/run_diff_ik.py script with my VIPER_HIGH_PD_CFG robot. The robot goes to the initial pose, but it does not move after that. I would expect the end effector to try to reach the target pose. This is what it looks like:

In the run_diff_ik.py file, I replaced the Franka robot with

robot_entity_cfg = SceneEntityCfg("robot", joint_names=["waist", "shoulder",
        "elbow", "forearm_roll", "wrist_angle", "wrist_rotate",
        "left_finger", "right_finger"], body_names=["gripper_prop_link"])

In comparison, this is what the Franka arm looks like when running that run_diff_ik.py script (expected behavior):


Questions

  1. Does anyone know why the converted articulated USD is falling under gravity despite the stiffness and damping being set for the joints?
  2. Additionally, if I set disable_gravity to True, why does the robot only go to the initial requested pose, but not move to the commanded joints?

These two cases (the robot falling under gravity and the robot not moving at all when disable_gravity=True) seems to suggest that the robot is unable to be commanded at all.


Additional context

  • The reason why I am not using the URDF convertor (which is probably more supported) is because the ViperX 300 arm URDF is in the XACRO format, and I haven’t been able to convert that to a URDF.

  • For reference, this is my viper.py configuration file:

    import omni.isaac.lab.sim as sim_utils
    from omni.isaac.lab.actuators import ImplicitActuatorCfg
    from omni.isaac.lab.assets.articulation import ArticulationCfg
    
    ##
    # Configuration
    ##
    
    VIPER_CFG = ArticulationCfg(
        spawn=sim_utils.UsdFileCfg(
            usd_path="/home/maggiewang/Workspace/IsaacLab/source/extensions/omni.isaac.lab_assets/data/Robots/VX300s/vx300s_again.usd",
            activate_contact_sensors=False,
            rigid_props=sim_utils.RigidBodyPropertiesCfg(
                disable_gravity=False,
                max_depenetration_velocity=5.0,
            ),
            articulation_props=sim_utils.ArticulationRootPropertiesCfg(
                enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0
            ),
            collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
        ),
        init_state=ArticulationCfg.InitialStateCfg(
            joint_pos={
                "waist": 0.0,
                "shoulder": -0.96,
                "elbow": 1.16,
                "forearm_roll": 0.0,
                "wrist_angle": -0.3,
                "wrist_rotate": 0.0,
                "left_finger": 0.024,
                "right_finger": -0.024,
            },
        ),
        actuators={
            "waist": ImplicitActuatorCfg(
                joint_names_expr=["waist"],
                effort_limit=35.0,
                velocity_limit=2.286,  # NOTE this actually doesn't set anything, need to set it in usd itself
                stiffness=25.0,
                damping=2.86,
            ),
            "shoulder": ImplicitActuatorCfg(
                joint_names_expr=["shoulder"],
                effort_limit=57.0,
                velocity_limit=2.286,
                stiffness=76.0,
                damping=6.25,
            ),
            "elbow": ImplicitActuatorCfg(
                joint_names_expr=["elbow"],
                effort_limit=25.0,
                velocity_limit=2.286,
                stiffness=106.0,
                damping=8.15,
            ),
            "forearm_roll": ImplicitActuatorCfg(
                joint_names_expr=["forearm_roll"],
                effort_limit=10.0,
                velocity_limit=2.286,
                stiffness=35.0,
                damping=3.07,
            ),
            "wrist_angle": ImplicitActuatorCfg(
                joint_names_expr=["wrist_angle"],
                effort_limit=35.0,
                velocity_limit=2.286,
                stiffness=8.0,
                damping=1.18,
            ),
            "wrist_rotate": ImplicitActuatorCfg(
                joint_names_expr=["wrist_rotate"],
                effort_limit=35.0,
                velocity_limit=2.286,
                stiffness=7.0,
                damping=7,
            ),
            "gripper": ImplicitActuatorCfg(
                joint_names_expr=["left_finger", "right_finger"],
                effort_limit=35.0,
                velocity_limit=2.286,
                stiffness=300.0,
                damping=1000.0,
            ),
        },
        soft_joint_pos_limit_factor=1.0,
    )
    """Configuration of Viper robot."""
    
    
    VIPER_HIGH_PD_CFG = VIPER_CFG.copy()
    VIPER_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True
    VIPER_HIGH_PD_CFG.actuators["waist"].stiffness = 400.0
    VIPER_HIGH_PD_CFG.actuators["waist"].damping = 80.0
    VIPER_HIGH_PD_CFG.actuators["shoulder"].stiffness = 400.0
    VIPER_HIGH_PD_CFG.actuators["shoulder"].damping = 80.0
    VIPER_HIGH_PD_CFG.actuators["elbow"].stiffness = 400.0
    VIPER_HIGH_PD_CFG.actuators["elbow"].damping = 80.0
    
  • This is my run_diff_ik.py file:

    # Copyright (c) 2022-2024, The Isaac Lab Project Developers.
    # All rights reserved.
    #
    # SPDX-License-Identifier: BSD-3-Clause
    
    """
    This script demonstrates how to use the differential inverse kinematics controller with the simulator.
    
    The differential IK controller can be configured in different modes. It uses the Jacobians computed by
    PhysX. This helps perform parallelized computation of the inverse kinematics.
    
    .. code-block:: bash
    
        # Usage
        ./isaaclab.sh -p source/standalone/tutorials/05_controllers/ik_control.py
    
    """
    
    """Launch Isaac Sim Simulator first."""
    
    import argparse
    
    from omni.isaac.lab.app import AppLauncher
    
    # add argparse arguments
    parser = argparse.ArgumentParser(description="Tutorial on using the differential IK controller.")
    parser.add_argument("--robot", type=str, default="franka_panda", help="Name of the robot.")
    parser.add_argument("--num_envs", type=int, default=128, help="Number of environments to spawn.")
    # append AppLauncher cli args
    AppLauncher.add_app_launcher_args(parser)
    # parse the arguments
    args_cli = parser.parse_args()
    
    # launch omniverse app
    app_launcher = AppLauncher(args_cli)
    simulation_app = app_launcher.app
    
    """Rest everything follows."""
    
    import torch
    
    import omni.isaac.lab.sim as sim_utils
    from omni.isaac.lab.assets import AssetBaseCfg
    from omni.isaac.lab.controllers import DifferentialIKController, DifferentialIKControllerCfg
    from omni.isaac.lab.managers import SceneEntityCfg
    from omni.isaac.lab.markers import VisualizationMarkers
    from omni.isaac.lab.markers.config import FRAME_MARKER_CFG
    from omni.isaac.lab.scene import InteractiveScene, InteractiveSceneCfg
    from omni.isaac.lab.utils import configclass
    from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR
    from omni.isaac.lab.utils.math import subtract_frame_transforms
    
    ##
    # Pre-defined configs
    ##
    from omni.isaac.lab_assets import FRANKA_PANDA_HIGH_PD_CFG, VIPER_HIGH_PD_CFG, UR10_CFG  # isort:skip
    
    
    @configclass
    class TableTopSceneCfg(InteractiveSceneCfg):
        """Configuration for a cart-pole scene."""
    
        # ground plane
        ground = AssetBaseCfg(
            prim_path="/World/defaultGroundPlane",
            spawn=sim_utils.GroundPlaneCfg(),
            init_state=AssetBaseCfg.InitialStateCfg(pos=(0.0, 0.0, -1.05)),
        )
    
        # lights
        dome_light = AssetBaseCfg(
            prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
        )
    
        # mount
        table = AssetBaseCfg(
            prim_path="{ENV_REGEX_NS}/Table",
            spawn=sim_utils.UsdFileCfg(
                usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/Stand/stand_instanceable.usd", scale=(2.0, 2.0, 2.0)
            ),
        )
    
        # articulation
        if args_cli.robot == "franka_panda":
            robot = VIPER_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
        elif args_cli.robot == "ur10":
            robot = UR10_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
        else:
            raise ValueError(f"Robot {args_cli.robot} is not supported. Valid: franka_panda, ur10")
    
    
    def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
        """Runs the simulation loop."""
        # Extract scene entities
        # note: we only do this here for readability.
        robot = scene["robot"]
    
        # Create controller
        diff_ik_cfg = DifferentialIKControllerCfg(command_type="pose", use_relative_mode=False, ik_method="dls")
        diff_ik_controller = DifferentialIKController(diff_ik_cfg, num_envs=scene.num_envs, device=sim.device)
    
        # Markers
        frame_marker_cfg = FRAME_MARKER_CFG.copy()
        frame_marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
        ee_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_current"))
        goal_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_goal"))
    
        # Define goals for the arm
        ee_goals = [
            [0.5, 0.5, 0.7, 0.707, 0, 0.707, 0],
            [0.5, -0.4, 0.6, 0.707, 0.707, 0.0, 0.0],
            [0.5, 0, 0.5, 0.0, 1.0, 0.0, 0.0],
        ]
        ee_goals = torch.tensor(ee_goals, device=sim.device)
        # Track the given command
        current_goal_idx = 0
        # Create buffers to store actions
        ik_commands = torch.zeros(scene.num_envs, diff_ik_controller.action_dim, device=robot.device)
        ik_commands[:] = ee_goals[current_goal_idx]
    
        # Specify robot-specific parameters
        if args_cli.robot == "franka_panda":
            # robot_entity_cfg = SceneEntityCfg("robot", joint_names=["panda_joint.*"], body_names=["panda_hand"])
            robot_entity_cfg = SceneEntityCfg("robot", joint_names=["waist", "shoulder",
                    "elbow", "forearm_roll", "wrist_angle", "wrist_rotate",
                    "left_finger", "right_finger"], body_names=["gripper_prop_link"])
        elif args_cli.robot == "ur10":
            robot_entity_cfg = SceneEntityCfg("robot", joint_names=[".*"], body_names=["ee_link"])
        else:
            raise ValueError(f"Robot {args_cli.robot} is not supported. Valid: franka_panda, ur10")
        # Resolving the scene entities
        robot_entity_cfg.resolve(scene)
        # Obtain the frame index of the end-effector
        # For a fixed base robot, the frame index is one less than the body index. This is because
        # the root body is not included in the returned Jacobians.
        if robot.is_fixed_base:
            ee_jacobi_idx = robot_entity_cfg.body_ids[0] - 1
        else:
            ee_jacobi_idx = robot_entity_cfg.body_ids[0]
    
        # Define simulation stepping
        sim_dt = sim.get_physics_dt()
        count = 0
        # Simulation loop
        while simulation_app.is_running():
            # reset
            if count % 150 == 0:
                # reset time
                count = 0
                # reset joint state
                joint_pos = robot.data.default_joint_pos.clone()
                joint_vel = robot.data.default_joint_vel.clone()
                robot.write_joint_state_to_sim(joint_pos, joint_vel)
                robot.reset()
                # reset actions
                ik_commands[:] = ee_goals[current_goal_idx]
                joint_pos_des = joint_pos[:, robot_entity_cfg.joint_ids].clone()
                # reset controller
                diff_ik_controller.reset()
                diff_ik_controller.set_command(ik_commands)
                # change goal
                current_goal_idx = (current_goal_idx + 1) % len(ee_goals)
            else:
                # obtain quantities from simulation
                jacobian = robot.root_physx_view.get_jacobians()[:, ee_jacobi_idx, :, robot_entity_cfg.joint_ids]
                ee_pose_w = robot.data.body_state_w[:, robot_entity_cfg.body_ids[0], 0:7]
                root_pose_w = robot.data.root_state_w[:, 0:7]
                joint_pos = robot.data.joint_pos[:, robot_entity_cfg.joint_ids]
                # compute frame in root frame
                ee_pos_b, ee_quat_b = subtract_frame_transforms(
                    root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_pose_w[:, 0:3], ee_pose_w[:, 3:7]
                )
                # compute the joint commands
                joint_pos_des = diff_ik_controller.compute(ee_pos_b, ee_quat_b, jacobian, joint_pos)
    
            # apply actions
            robot.set_joint_position_target(joint_pos_des, joint_ids=robot_entity_cfg.joint_ids)
            scene.write_data_to_sim()
            # perform step
            sim.step()
            # update sim-time
            count += 1
            # update buffers
            scene.update(sim_dt)
    
            # obtain quantities from simulation
            ee_pose_w = robot.data.body_state_w[:, robot_entity_cfg.body_ids[0], 0:7]
            # update marker positions
            ee_marker.visualize(ee_pose_w[:, 0:3], ee_pose_w[:, 3:7])
            goal_marker.visualize(ik_commands[:, 0:3] + scene.env_origins, ik_commands[:, 3:7])
    
    
    def main():
        """Main function."""
        # Load kit helper
        sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device)
        sim = sim_utils.SimulationContext(sim_cfg)
        # Set main camera
        sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
        # Design scene
        scene_cfg = TableTopSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
        scene = InteractiveScene(scene_cfg)
        # Play the simulator
        sim.reset()
        # Now we are ready!
        print("[INFO]: Setup complete...")
        # Run the simulator
        run_simulator(sim, scene)
    
    
    if __name__ == "__main__":
        # run the main function
        main()
        # close sim app
        simulation_app.close()
    

Thank you for your interest in Isaac Lab, our apologies for the late response. To ensure efficient support and collaboration, please submit your topic to its GitHub repo following the instructions provided on Isaac Lab’s Contributing Guidelines regarding discussions, submitting issues, feature requests, and contributing to the project.

We appreciate your understanding and look forward to assisting you.