Gain Tuner Extension#
About#
The Gain Tuner Extension is used to tune the stiffness and damping gains of a selected Articulation. This extension is useful when importing any new robot or when needing to fine tune the gains of an existing robot.
This extension is enabled by default. If it is ever disabled, it can be re-enabled from the Extension Manager by searching for isaacsim.robot_setup.gain_tuner
.
To access this Extension, go to the top menu bar and click Tools > Robotics > Asset Editors > Gain Tuner. Open your robot asset, which will populate the Gain Tuner Select Robot UI element with possible robot choices. The order of opening gain tuner window or opening the asset should not make any difference.

User Guide#
Overview#
The purpose of the Gain Tuner is to find a pair of stiffness and damping gains for each robot joint so that the robot is able to follow commanded trajectories according to the robot’s expected behavior.
The Gain Tuner offers a set of tests that allow the user to quickly assess the quality of the current set of gains as well as a utility for tuning gains manually. This tutorial will take the user through:
Tuning Gains: A utility for tuning the gains for the robot.
Gains Test: A utility for testing the robot’s behavior with a continuous sinusoidal or Step Function trajectory for each joint within the Robot’s Limits, maximum velocities and accelerations.
Test Results: A plot of the results of the gains tests on the tracked Joint Positions and Velocities, compared against the commanded trajectory.
The Gain Tuner extension is designed to be used on Robot assets, which are USD assets that contain the Robot Schema applied.
Tuning Gains#
The Joint Gains are a pair of Stiffness and Damping values that are used to drive the joint. They are applied to the joint in the form of a drive that applies an effort (Force/Torque) to the joint, based on the error between the desired position, velocity or both. This Effort is computed as:
Where \(K_p\) is the Stiffness and \(K_d\) is the Damping.
From this formula, we can describe the different modes of the joint drive:
Position Drive: When the joint drive is in position mode, the desired position is the target position. This requires the Stiffness to be Greater than 0, and damping to be any value
Velocity Drive: When the joint drive is in velocity mode, the desired position is the current position, and the desired velocity is the target velocity. This requires the Stiffness to be 0, and damping to be any value.
None: When the joint drive is in none mode, the joint drive is not active. The joint can still be controlled by applying a direct effort. This requires the Stiffness to be 0, and damping to be 0.
Mimic: When the joint drive is in mimic mode, the joint drive is driven by the mimic joint. This means that the joint drive will not be active, but the mimic joint’s attributes of Natural Frequency and Damping Ratio can still be configured through the Tuner.
This Dampener-Spring model can also be described in terms of the natural frequency and damping ratio:
Where \(\omega_n\) is the natural frequency and \(\zeta\) is the damping ratio, and \(m\) is the computed joint inertia based on the mass of the robot at both sides of the joint. The damping ratio is such that \(\zeta = 1.0\) is a critically damped system, \(\zeta < 1.0\) is underdamped, and \(\zeta > 1.0\) is overdamped.
From the above formula, we can see that there are Two Ways to Tune Gains:
Directly editing Stiffness and Damping values: On the joints table, You can directly edit the Stiffness and Damping values for each joint.
Natural Frequency: The Gain tuner can also automatically compute the Stiffness and Damping values for each joint based on the desired natural frequency and damping ratio.
Note
Because the robot is a structure that is made of multiple links and moving joints, the natural frequency of each joint is dependent on the robot’s configuration. To establish a standard, we use the natural frequency of the robot at its home configuration.
Tuning Options#
In the Tuning Options, users can select the tuning mode between Stiffness and Natural Frequency. On the joints table, users can see the following options:
Mode: The mode of the joint drive (Position, Velocity, None, Mimic)
Type: The type of the joint drive (Force, Acceleration). In Force, the effort is applied directly to the joint. In Acceleration, the effort is Normalized by the joint’s mass, and is thus invariant to the robot’s configuration, behaving as an ideal actuator.
Stiffness (Stiffness Mode): The stiffness of the joint drive. Changing this will lead to a change in the natural frequency of the joint.
Damping (Stiffness Mode): The damping of the joint drive. Changing this will lead to a change in the damping ratio of the joint.
Natural Frequency (Natural Frequency Mode): The natural frequency of the joint drive.
Damping Ratio (Natural Frequency Mode): The damping ratio of the joint drive.
The configurable Degrees of Freedom (DOF) of the robot are displayed in accordance with what is defined in the Robot’s Joints list.
Saving Gains to the Asset#
Following the NVIDIA Isaac Sim Asset Structure, Joint gains would be a physics configuration, and should ideally be saved on the physics configuration layer. To facilitate this, The Save Gains to Physics Layer
button on the UI searches for the Asset’s physics layer where the joint is defined, and applies the updated gains to that layer. If you don’t want or don’t have permission to save on that file, you can just save the currently open stage instead to author an override to the joint target values locally.
Gains Tests#
The Gains Tests are a set of tests that allow the user to test the robot’s behavior with a continuous sinusoidal or Step Function trajectory for each joint within the Robot’s Limits, maximum velocities and accelerations.
The test is divided by sequences, and each sequence is a group of joints to be tested together. The sequence is defined per joint, and is an index of the order in which the test will be run. For each sequence, the robot resets to the initial configuration, and then the test is run for the provided duration. In addition to that, each joint can be configured to have an individual test setting, which contains the following parameters:
Common Test Settings#
Test: Check to run the test.
Period: The period of the waveform.
Phase: The phase of the waveform.
Sinusoidal#
Amplitude: The amplitude of the waveform, from 0 to 100%
Offset: The offset of the waveform, from 0 to 100%.
Step Function#
Step Minimum: The minimum value of the waveform, in the joint value units of measurement.
Step Maximum: The maximum value of the waveform, in the joint value units of measurement.
In the tests, we are sending only Position commands for Position drives, and velocity commands for velocity Drives. In position commands, the target velocities are always zero, such that the joint damping is properly evaluated. In a real control scenario, a proper trajectory command should be ideally sent, where the velocity command is equivalent to the integrated positions of the designated trajectory.

Visualize Results#
The results of the tests are visualized in the form of a plot, where the tracked Joint Positions and Velocities are compared against the commanded trajectory. Select the desired joint to visualize the results on the left panel, and their respective test results will be displayed on the plots. The test results are color-coded by joint, with the measured values being a faded version of the commanded trajectory’s color.
Even if the joint is not listed on the Robot Schema, it will still be visualized in the plots, if it’s part of the physical robot.
To select more than one joint, users can hold down the control key and click on the desired joint, or select the first joint and then hold down the shift key and click on the last desired joint, and all joints between them will be selected.

Note
The visualization results are only available when the tests are finished running, so depending on the configuration of the tests, it may take some time to get the results.
Further Learning#
The Tutorial 11: Tuning Joint Drive Gains tutorial goes into more specific detail about the physical mechanics relating joint gains to derived motions.