Intro
In this tutorial, you will learn how to import your robot from a URDF file into Isaac Sim and convert it to the USD file format. I will walk you through a hands-on example using the SO-ARM100 robot arm, which is part of my community project series on robotics simulation and reinforcement learning.
I had the honor of joining the NVIDIA Omniverse livestream, where I presented a live walkthrough on training the SO-ARM100 in Isaac Lab, starting directly from the URDF file. I was joined by NVIDIA Omniverse engineers who offered valuable insights and answered many community questions. This tutorial, however, will be a more condensed and focused version. It will include not only a walkthrough but also a deeper look into how the open source URDF Importer in Isaac Sim actually works.
- If you are interested in the livestream you can watch it here, otherwise scroll down to continue to the tutorial.
Prerequisites
1) Isaac Sim → Learn more here:
Isaac Sim (+ Installation)
2) What exactly is URDF?
The Unified Robot Description Format is an XML-based format used to describe robot models in ROS. It defines how the links and joints of a robot are connected, including properties like mass, inertia, collision shapes, visuals, and more. If you want a really good introduction to URDF, I highly recommend the video by Articulated Robotics where he explains everything from the ground up. He also recently published an overview of Isaac Sim that I suggest checking out as well.
3) USD File Format → Learn more here:
OpenUSD
Why do we need the URDF importer in Isaac Sim?
All Omniverse applications, including Isaac Sim, operate using USD — the Universal Scene Description, also known as openUSD. USD is a scene graph file format that defines everything in your simulation. The entire simulation scene is a USD file, and so are all its subcomponents — including materials, lights, and objects. When we import a robot from a URDF file, it becomes a USD asset, enabling us to manipulate it in Isaac Sim, connect it to ROS, or train it using reinforcement learning in Isaac Lab.
Hands-On Example using the SO-ARM100
- Check out the docs here:
URDF Importer Extension — Isaac Sim Documentation
- Check out the official tutorial for the Franka Arm here:
Tutorial: Import URDF — Isaac Sim Documentation
- Clone / Download this repo:
- Find the URDF for this project here:
- Choose
SO-ARM100\URDF\SO_5DOF_ARM100_8j_URDF.SLDASM\urdf
SO_5DOF_ARM100_8j_URDF.SLDASM.urdf
There are some discrepancies in the naming of joints, especially “Moving Jaw” is missing an underscore: “Moving_Jaw”. Please refer to the tutorial video for a fix.
Or use the URDF from my existing Github repo:
Steps
- Open Isaac Sim → File → Import → Locate URDF file
- Choose the settings as the following (explained & shown in the video)
Joint Physics: Computing Stiffness and Damping in URDF Importers
This tutorial explains how the URDF importer calculates physically accurate joint parameters for robotic simulations.
- Let us watch the clip from Michael Gussert, explaining how it is modeled in Isaac Sim
- And another clip explaining what Stiffness and Damping do
Overview of the Calculation Process
- First, the importer computes joint inertia by calculating accumulated inertias from both sides of the joint
- Then it calculates stiffness using a spring-mass-damper physics model
- Finally, it computes appropriate damping for stable joint control
From the Docs:
URDF Importer Extension — Isaac Sim Documentation
- Stiffness: Edit the joint drive stiffness and damping directly.
- Natural Frequency: Computes the Joint drive stiffness and Damping ratio based on the desired natural frequency using the formula:
where f is the natural frequency, r is the damping ratio, and total equivalent inertia at the joint. The damping ratio is such that r = 1.0 is a critically damped system, r < 1.0 is underdamped, and r > 1.0 is overdamped.
Stiffness Calculation
The stiffness calculation is handled by the computeSimpleStiffness function:
float computeSimpleStiffness(const UrdfRobot& robot, std::string joint, float naturalFrequency) {
float inertia = 1.0f;
if (robot.joints.at(joint).drive.driveType == UrdfJointDriveType::FORCE) {
inertia = robot.joints.at(joint).jointInertia;
}
return inertia * naturalFrequency * naturalFrequency;
}
This uses the physics formula:
- stiffness = inertia × (naturalFrequency)²
Damping Calculation
The damping calculation is done directly during joint configuration:
joint.second.drive.damping = joint.second.jointInertia * 2 *
joint.second.drive.naturalFrequency *
joint.second.drive.dampingRatio;
This uses the critical damping formula:
- damping = jointInertia × 2 × naturalFrequency × dampingRatio
Joint Inertia Calculation
The joint inertia is calculated through:
- compute_accumulated_inertias - Traverses joint tree in both directions
- compute_parallel_axis_inertia - Applies parallel axis theorem
- computeEquivalentInertia - Combines inertias using formula: m1 * m2 / (m1 + m2)
Calculating Accumulated Inertias
void compute_accumulated_inertias(const UrdfRobot& robot,
const std::string& joint_name,
Matrix33& backward_accumulated_inertia,
Matrix33& forward_accumulated_inertia) {
// Reset accumulated inertias
backward_accumulated_inertia = Matrix33();
forward_accumulated_inertia = Matrix33();
// ... traverses joint tree backward and forward from the specified joint
// ... accumulates inertia contributions from connected links
}
Equivalent Inertia Calculation
float computeEquivalentInertia(const float m1, const float m2) {
if (m1 + m2 > 0) {
return m1 * m2 / (m1 + m2);
}
return 0;
}
Unit Conversion
- Natural Frequency: The importer expects angular frequency in rad/s, not Hz
- To convert: ω = 2π × f (example: 5 Hz = 31.416 rad/s)
- GUI Display: Values are shown "per degree" but calculated "per radian"
- Multiply GUI values by 57.3 (degrees per radian)
Why This Matters
Proper stiffness and damping values are crucial for realistic joint behavior in simulation:
- Too low stiffness = floppy, unresponsive joints
- Too high stiffness = numerical instability
- Proper damping prevents oscillation while allowing natural movement
Determining Values for Real Robots
Documentation: Tuning Joint Drive Gains — Isaac Sim Documentation
For real robots, determining optimal stiffness and damping values can be approached several ways:
- Consult manufacturer specifications (if available)
- Use system identification techniques (frequency response analysis)
- Apply step inputs and measure oscillation frequency and decay
- Iterative experimental testing (start conservative, gradually adjust)
For example, with the SO-ARM100 robot, there are no manufacturer specifications available, and the accuracy of inertia values in the provided URDF is uncertain. In such cases:
While formal approaches like vibration analysis or frequency sweep tests would provide accurate values, they often require specialized equipment and significantly more time than practical trial and error. For many applications, a systematic trial-and-error approach starting with conservative values is more efficient.
Literature-Based Parameter Recommendations
Research sources provide valuable guidance for selecting appropriate natural frequency and damping values:
Recommended Parameters for SO-ARM100
Based on the literature and the lightweight plastic construction of the SO-ARM100:
- Natural frequency (fₙ): 10 Hz
- Damping ratio (ζ): 0.7
This selection balances:
- The lower stiffness of plastic materials (closer to the cantilever cases)
- Need for reasonably fast settling in manipulation tasks
- The higher internal damping typical of plastic parts
Domain Randomization for Reinforcement Learning
As noted by Michael Gussert in the livestream, reinforcement learning offers an interesting solution to parameter uncertainty through domain randomization:
- Clipped from Livestream
- Instead of seeking exact parameter values, we can randomize joint parameters during training
- Parameters like mass, damping, stiffness, and friction are varied within reasonable ranges
- This helps close the sim-to-real gap by making policies robust to parameter variations
- Allows more room for error in the physical parameters without compromising performance
This approach is particularly valuable when exact dynamics modeling is difficult or impractical, as with the SO-ARM100 where specifications are incomplete.
Image from: Lilian Weng Domain Randomization for Sim2Real Transfer
Try out the Joints yourself using the Physics Inspector
- Under Tools → Physics → Physics Inspector you can test them out and also set various settings
- More in later videos
Last Step… Don’t Forget the Articulation Root
- Delete the Articulation Root from the joint and set it to a mesh or xform prim.