Skip to content

Navigation PID tuning (FW)

Jetrell edited this page Aug 23, 2025 · 16 revisions

This page is a work in progress until this message is removed

The aim of this page is to separate the tuning of the FW Navigation PIDs from the Navigation modes page. Its goal is also to have FW Nav PID tuning separate from MC Nav PID tuning. To de-clutter and make for easier reading.

Tip

There is also a companion wiki page GPS and Compass setup, that is essential reading beforehand. The Installation location, Setup and Calibration of the GNSS/Magnetometer module, to provide the best navigation performance achievable, is of absolute importance.
Accounting for this detail can make your build a greater success.

Caution

The Main Stabilization PID_FF, RATES and LEVEL controller MUST be tuned well before attempting to tune the navigation controllers.
With incorrectly tuned FeedForward, noticeable impacting navigation performance.
Take note of how the Rate/FF Auto-tune process is performed.

Tuning Altitude Controller - Z axis:

Inability to maintain altitude accuracy or reach a commanded climb rate can be due to a number of reasons:

  • Poor GNSS satellite accuracy and EPV position data - Ensure you have a HDOP less than 1.2 for best precision. And never above 1.8. See here
  • Main stabilization PID_FF, RATES, AUTO LEVEL TRIM or SERVO AUTOTRIM are poorly tuned.
  • The fuselage air inlet cooling hole is larger than the outlet, causing it to become pressurized. Leading to an incorrect barometric altitude read.
  • The control surface throws are too great or too little. Or its C.G. with respect to the aerofoils Center of Lift/Pressure is incorrect.
  • The motor thrust angle is incorrect.
  • Insufficient motor thrust - The airplanes thrust to weight ratio is too low.
  • High accelerometer vibrations from the prop(s) or motor(s) - Balance the propeller(s) and/or motor(s) if required, then apply software filters.
  • If all the previous conditions are satisfied - Incorrectly tuned POS_Z_D and/or FW_FF_PITCH or POS_Z_P, POS_Z_I.

Make sure those conditions are addressed first, before you attempt to tune the altitude PID's and climb rate settings.

ALTITUDE POS(VEL) PID Tuning:

Altitude is always referred too as the vertical or (Z) axis.

Tuning of an airplanes Z axis controller should be done on a day no colder than 5°C, for the best outcome. Due to the effect temperature has on the Baro and IMU.

The following settings can be accessed using the Configurator Tuning tab and Advanced Tuning tab. Or the CLI and CMS OSD stick menu's.

  • nav_fw_pos_z_p - Controls velocity to acceleration. Increasing the gain will provide a stronger elevator/pitch2throttle response to reach the required altitude target.
  • nav_fw_pos_z_i - Attempts to compensate for climb rate fluctuations cause by turbulence, thermals etc. Use sparingly. It can only do so much on a fixedwing platform.
  • nav_fw_pos_z_d - Attempts to anticipate the magnitude of the error and dampen the POS_Z_P and POS_Z_I response to the process variables rate of change. Too much damping can lead to the climb rate error becoming incorrectly predicted, causing oscillations when the initial climb is commanded, or when holding the target altitude. Even becoming more exaggerated by an incorrectly tuned fw_ff_pitch response.
    NOTE: This has been altered for INAV 9.0. To use a measurement snap-shot of the process variable, instead of the variables rate of change. Which smooths the operation of the altitude Velocity and Position controllers, on a broader range of airframes and setups.
  • nav_fw_pos_z_ff - Attempts to provide a faster control response to meet the require target, based on altitude and gyro rate data. Depending on the aircraft's build specifics, lowering POS_Z_D and increasing POS_Z_FF may help. * Not used with the altitude POSITION controller in INAV 9.0.
  • nav_fw_alt_control_response - Alters the altitude control response as the airplane gets closer to reaching the altitude target. Should be tuned together with POS_Z_D to get the best performance and trouble free use.
  • fw_ff_pitch - Passes the angular rate target directly to the servo mixer, bypassing the gyro PID loop stabilization.
  • nav_fw_auto_climb_rate- Maximum climb/descent rate in [cm/s], the airplane is allowed to reach in modes that control altitude.

Altitude control methods:

The settings for both altitude control methods where derived from multiple testers. This first group of settings should also work reasonably well with the 8.0 implementation of the altitude VELOCITY controller.
When used in INAV 9.0 release. The altitude VELOCITY controller is active by default. i.e. nav_fw_alt_use_position = OFF.
The accuracy of both controllers are similar. With little deviation observed when holding a fixed altitude.

Functionally, the altitude VELOCITY controller is more responsive. It will push the throttle and elevator considerably harder to reach the altitude target. This can make it less power efficient. However this maybe desirable if your airplane is flying a tight WP mission or RTH trackback, that has considerable altitude swings, and it is important to reach the altitude target quickly to clear an object in your flight path.

VELOCITY:
nav_fw_pos_z_p = 22
nav_fw_pos_z_i = 6
nav_fw_pos_z_d = 2
nav_fw_pos_z_ff = 25
nav_fw_alt_control_response = 45

When setting nav_fw_alt_use_position = ON in 9.0 and later. It provides a slightly more refined version of the old altitude POSITION controller used before INAV 8.0.

Functionally, the altitude POSITION controller is little less responsive than the altitude Velocity controller. Which makes it more power efficient when a climb is commanded. This maybe beneficial if extended flight time and power management is of importance to you.

POSITION:
nav_fw_pos_z_p = 30
nav_fw_pos_z_i = 5
nav_fw_pos_z_d = 11
nav_fw_alt_control_response = 40

Pitch2Throttle Tuning:

All the settings below work in conjunction with the nav_fw_pitch2thr command. And effect fixedwing altitude control response.

It basically multiplies the nav_fw_pitch2thr by nav_fw_climb_angle or nav_fw_dive_angle. To provide how many microSeconds Auto-Throttle will increase, as a result of each degree of positive pitch angle. Or decrease, as a result of each degree of negative pitch angle.

nav_fw_cruise_thr is the throttle value used when the airplane is flying level, when no nav_fw_pitch2thr is being applied.
nav_fw_pitch2thr should be tuned to work within the uS throttle constraints of nav_fw_min_thr and nav_fw_max_thr.

Example:
If nav_fw_pitch2thr = 12uS x nav_fw_climb_angle = 25° = 300uS. (The same will apply to nav_fw_dive_angle degrees.)
So if you have nav_fw_cruise_thr = 1450uS. Then you add 300uS to 1450uS = 1750uS. This means 1750uS is the maximum value nav_fw_max_thr will output to the motor, at a pitch climb angle of 25°.
However, in the above example, if nav_fw_pitch2thr was set lower. Auto-Throttle would fall short of reaching nav_fw_max_thr. This is why it has to be adjusted to suit your required Dive / Climb angle and Min / Max cruise throttle range.

To reduce the likelihood of pitch bobbing or porpoising, while in modes that hold altitude. nav_fw_pitch2thr_smoothing reduces harsh Auto-Throttle response, when flying close to level.
While nav_fw_pitch2thr_threshold sets a deadband region this many decidegrees above or below level flight, for the nav_fw_pitch2thr_smoothing to work within.

The settings below can also be tweaked to suit your desired rate of climb or dive. They too will alter the altitude controllers responsiveness.

Tuning Position Controller - XY axis:

Inability to obtain an accurate horizontal position can be caused by a number of reasons:

  • Poor GNSS satellite accuracy and EPH position data - Ensure you have a HDOP less than 1.2 for best precision. And never above 1.8. See here
  • Main stabilization PID_FF and RATES are poorly tuned.
  • SERVO AUTOTRIM is not tuned correctly.
  • The control surface throws are too great or too little. Or its C.G. with respect to the aerofoils Center of Lift/Pressure is incorrect.
  • Poorly Installed, Aligned or Calibrated magnetometer (compass) - If a magnetometer is used, read here to provide the best results.
  • High accelerometer vibrations from the motor(s) or prop(s). - Can lead to attitude and heading inaccuracy or drift.
  • If all the previous conditions are satisfied - Incorrectly tuned POS_XY_P, POS_XY_I or POS_HDG_P if nav_use_fw_yaw_control = ON

Make sure these hardware conditions are addressed first, before you attempt to tune the navigation POS, VEL and HEADING PID's.

Horizontal POS PID Tuning:

Tuning of an airplanes XY axis controllers should be done on a day no colder than 5°C, for the best outcome. This is due to the effect temperature has on the IMU.

When tuning the Nav XY controllers, you require a means to reference the WP markers, to real-time heading and turning positions.
This is best done by logging the flight data. And gauging the changes with one or all of the following software's: MWP Tools , INAV Blackbox Explorer or Blackbox Tools

The following settings can be accessed using the Configurator Tuning tab and Advanced Tuning tab. Or the CLI and CMS OSD stick menu's.

Position XY gains:

  • nav_fw_pos_xy_p - Controls how fast the airplane will attempt to use the roll and yaw axis to align its trajectory with the target position. This includes the strength it will apply to turning and re-aligning with the track after a turn.
  • nav_fw_pos_xy_i - Increasing this gain can compensate for trajectory drift caused by the wind. But should be used sparingly on elevon aircraft.
  • nav_fw_pos_xy_d - Increasing this gain can help smooth the P gain response. But if increased too much, it can cause over-shooting of the target trajectory alignment.
  • nav_fw_cruise_thr - Should be set to the airplanes optimal cruise speed. Keeping the average airspeed less than 75km/h, will obtain the highest accuracy.

Heading Yaw Tuning - XY axis:

The first step towards the use of fixedwing yaw control is to load the appropriate Servo or Motor mixer, to suit your airframes yaw stabilization and control method. This can be found in the MIXER Tab under MIXER PRESETS.
When the preset is selected, it will either add a Servo (smix)- Stabilized Yaw for rudder control. Or it will add two Motors (mmix) for differential thrust yaw control.

Fixedwing stabilization uses the TURN ASSIST feature to help maintain control over the aircraft. It is active in all navigation modes. But can be disabled in the modes tab if desired.

Fixedwing AutoTune does not operate on the yaw axis. This means the tuning has to be done manually.
The gains you derive when tuning the PID Yaw controller will differ, depending on the control method. With a Rudder inducing yaw rotation from control surface area and deflection. While Differential thrust or Vectored thrust does so actively. However a large rudder on an aerobatic 3D style airplane can also produce a considerable rotation rate.

The default fw_p_yaw, fw_i_yaw, fw_d_yaw, fw_ff_yaw and yaw_rate are safe values to start tuning from.
Keep in mind that the smix weight and/or Servo min/max output travels will work with fw_ff_yaw to achieve the desired yaw rate from a Rudder.
While the mmix motor yaw weight works together with fw_ff_yaw to achieve the desired yaw rate from Differential thrust. The default motor mixer weight for yaw is [0.3 -0.3]. When increasing the yaw motor mixer weight, it should be done in harmony with the setting mentioned hereafter.
More mixer related information can be found here.

Yaw axis tuning should only be attempted after you have first successfully tuned the airplane on the roll and pitch axis.

Tuning the yaw axis in ANGLE or ACRO can be made easier if you setup inflight tuning.
Once the tuning in those modes is completed. It is important to test its operation in Navigation modes, which includes RTH. The navigation controllers can cause undesirable yaw-roll coupling if too much yaw and roll are called for at the same time. For this reason it is important to tone-down the way yaw and roll work together in turns, by altering the settings below for safer tuning -

nav_fw_bank_angle = 30
nav_fw_control_smoothness = 9
heading_hold_rate_limit = 60
nav_use_fw_yaw_control = ON

Once tuned, these values may be increased incrementally if you find the airplane turns smoothly with no undesirable results.

Heading and related gains:

  • nav_fw_heading_p - Sets the strength the IMU heading target will be held. Heading data is updated from the GNSS course and/or mag bearing.
  • nav_use_fw_yaw_control- When enabled, it will activate the fixedwing yaw heading controller settings below. TURN ASSIST will allow it to be used with elevon aircraft. But it will not experience the full benefits of an airplane that has yaw control.
  • nav_fw_pos_hdg_p - Sets the strength the heading trajectory target is tracking.
  • nav_fw_pos_hdg_i - When used sparingly, it can filter-out heading target drift.
  • nav_fw_pos_hdg_d - Can smooth abrupt heading irregularity. But better suited to aircraft that have a means of yaw control.
  • heading_hold_rate_limit - Limits the yaw induced rotation rate the HEADING_HOLD controller can request from PID controller inner loop. It's independent from manual yaw rate and only active when HEADING_HOLD NAV flight modes are in use. The default value is more suited to copters, and should be used cautiously on planes that have yaw control, if nav_fw_control_smoothness is default or set below 7.
  • nav_cruise_yaw_rate - Sets the yaw rotation rate in degrees that the airplane can be commanded via stick input, while in Cruise/CourseHold modes.
  • fw_yaw_iterm_freeze_bank_angle - When enabled, it can help reduce the effect of the rudder counteracting aileron bank turns, by reducing yaw i-term error accumulation. It is only used for ANGLE, HORIZON or ACRO modes. It is not active in navigation modes, unless TURN ASSIST is disabled.

In my experience. Enabling the nav_fw_pos_hdg controller combined with an airplane that has yaw control. i.e. A Rudder, Differential thrust or Vectored thrust, when those yaw gains are tuned. Will provide the most accurate turn/track response in a waypoint mission or RTH Trackback.

The use of a magnetometer can help argument the GNSS heading and wind estimation, to provide faster correction in turns. But it must be setup and calibrated correctly. Or it will make performance even worse.

Tuning Rangefinder:

The Rangefinder (surface) gains should only be tuned after the Z navigation PID's are optimally tuned.

When a Lidar/Sonar sensor is selected via its Type or MSP. That sensor will actively feed the altitude estimator, regardless of the sensors operational range. However, over certain types of terrain, the sensor can occasionally read a false altitude spike. This has been known to cause a temporary ghost climbing action. If you experience this, it may be beneficial to disable the sensor in the Configuration tab.
NOTE: This issue has been resolved for INAV 9.0.

Rangefinder - Lidar or Sonar altitude terrain settings and sensor weights:

  • rangefinder_median_filter - Enables a 3-point median filter to helps smooth out altitude variations in the readout.
  • nav_max_terrain_follow_alt - Maximum allowable distance above the ground for altitude tracking in [CM], that directly maps throttle to altitude.
  • inav_max_surface_altitude - Maximum allowable altitude [CM] for the vertical position estimators validity check over a set time period.
  • inav_w_z_surface_p - Weight applied to the Rangefinders estimated altitude. When a rangefinder is present, within its operational distance above the ground.
  • inav_w_z_surface_v - Weight applied to the Rangefinders estimated climb rate. When a rangefinder is present, within its operational distance above the ground.

Tip

When choosing a Lidar rangefinder for fixedwing landing assistance. Ensure you do not purchased a cheaper unit with minimal range. e.g. 2meters or less. Such Lidar sensors have great difficulty working at even one quarter of their recommended range in direct sun light. Always select a higher quality unit with a stronger laser diode and lens, to provide more operational range.

Optical-flow is not available for fixedwing use, due to the speed airplanes travel across the ground. And the inherent range limitation of these sensors.

WIKI TOPICS

Wiki Home Page

INAV Version Release Notes

8.0.0 Release Notes
7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes

QUICK START GUIDES

Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md

Connecting to INAV

Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\

Flashing and Upgrading

Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md

Setup Tab
Live 3D Graphic & Pre-Arming Checks

Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration

Alignment Tool Tab
Adjust mount angle of FC & Compass

Ports Tab
Map Devices to UART Serial Ports

Receiver Tab
Set protocol and channel mapping

Mixer Tab
Set aircraft type and how its controlled

Outputs Tab
Set ESC Protocol and Servo Parameters

Modes Tab
Assign flight modes to transmitter switches
Standard Modes
Navigation Modes
Return to Home
Fixed Wing Autolaunch
Auto Launch

Configuration Tab
No wiki page currently

Failsafe Tab
Set expected behavior of aircraft upon failsafe

PID Tuning

Navigation PID tuning (FW)
Navigation PID tuning (MC)
EZ-Tune
PID Attenuation and scaling
Tune INAV PID-FF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md

GPS

GPS and Compass setup
GPS Failsafe and Glitch Protection

OSD and VTx

DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md

LED Strip

DevDocs LedStrip.md

ADVANCED

Programming

DevDocs Programming Framework.md

Adjustments

DevDocs Inflight Adjustments.md

Mission Control

iNavFlight Missions
DevDocs Safehomes.md

Tethered Logging

Log when FC is connected via USB

Blackbox

DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md

CLI

iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md

VTOL

DevDocs MixerProfile.md
DevDocs VTOL.md

TROUBLESHOOTING

"Something" is disabled Reasons
Blinkenlights
Sensor auto detect and hardware failure detection Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane

ADTL TOPICS, FEATURES, DEV INFO

AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Features safe to add and remove to fit your needs.
Developer info
INAV MSP frames changelog
INAV Remote Management, Control and Telemetry
Lightweight Telemetry (LTM)
Making a new Virtualbox to make your own INAV
MSP Navigation Messages
MSP V2
OrangeRX LRS RX and OMNIBUS F4
Rate Dynamics
Target and Sensor support
Ublox 3.01 firmware and Galileo
DevDocs Controls
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md

OLD LEGACY INFO

Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
iNav Telemetry
UAV Interconnect Bus
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md
DevDocs INAV_Autolaunch.pdf

Clone this wiki locally