Navigation PID tuning (MC) - iNavFlight/inav GitHub Wiki
This page is a work in progress until this message is removed
The aim of this page is to separate the tuning of the MC Navigation PIDs from the Navigation modes page. Its goal is also to have MC Nav PID tuning separate from FW 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 providing the best navigation performance achievable, is of absolute importance. Accounting for this detail can make your build a great success, or a disappointment if not done correctly.
[!Caution] When tuning all navigation PID's. Bear in mind, over-tuning their gains will not always react in the same way as over-tuning the main stabilization PID's, which will lead to oscillations on that axis. Instead, over-tune and saturating some navigation PID gain terms, will in effect provide a poorer control response, equivalent to under-tuning those same gains. Log data must be used as reference.
The Main Stabilization PID_CD and LEVEL controllers MUST be tuned before attempting to tune the navigation controllers. This is because the output from the navigation controllers are place into action through the main stabilization PID controllers.
Tuning Altitude Controller - Z axis:
Inability to maintain altitude can be caused by a number of reasons:
- Insufficient ALT_P, ALT_I and/or VEL_P, VEL_I - The default multicopter Altitude PID gains are set conservative for safety.
- Non-functional barometer - Go to the Configurator "Sensors tab" and verify that barometer graph changes as you move the copter up and down.
- Poor GNSS satellite accuracy and EPV altitude data - Ensure you have a HDOP less than 1.2 for best precision. And never above 1.8. Possible causes
- Seriously under-powered copter - ALTHOLD is only able to compensate to some degree. If your copter hovers at 1700 linear throttle without any expo, ALTHOLD might fail to compensate.
- Gaining altitude during fast flight - Can be caused by increased air pressure being applied to the barometer. This is measured as a reduction in altitude - Try covering your barometer with open-cell foam.
- Copter climbs vertically at a high rate, for a time - High accelerometer vibrations from the motors, props or frame resonance.
Make sure these hardware conditions are addressed first, before you even attempt to tune the nav Altitude POS and VEL PID's.
The following settings can be accessed using the Configurator CLI or Tuning tab under Additional PID Gains. Or by the CMS OSD stick menu's.
Altitude is referred too as the vertical or (Z) axis.
- ALT P
nav_mc_pos_z_p
- defines how fast copter will attempt to compensate for altitude error (converts alt error to desired climb rate) - ALT I
nav_mc_auto_climb_rate
- defines how fast copter will accelerate to reach desired climb rate - VEL P
nav_mc_vel_z_p
- defines how much throttle the copter will add to achieve the desired acceleration/deceleration required to meet the ALT_P and ALT_I targets. - VEL I
nav_mc_vel_z_i
- controls compensation for hover throttle, based on vertical air movement, thermals or ground-effect. Too much VEL I will lead to vertical oscillations, too low VEL I will cause drops or jumps when ALTHOLD is enabled. - VEL D
nav_mc_vel_z_d
- Acts as a dampener for VEL P and VEL I, to smooth their response and reduce oscillations caused by sensor variations.
ALTITUDE POS + VEL PID Tuning:
Try a small experiment: Make sure the barometer is well isolated. You may also want to reduce baro weight.
Tuning of copter z axis is best performed on a day no colder than 10°C. Due to the effect temperature has on the Baro and IMU.
-
set
inav_w_z_baro_p = 0.5
and ALT Pnav_mc_pos_z_p = 0
and try flying. This way the controller will attempt to keep zero climb rate without any reference to altitude. The quad should slowly drift either up or down. If it would be jumping up and down, your VELnav_mc_vel_z
gains are too high. -
As a second step you can try zeroing out VEL P
nav_mc_vel_z_p
and VEL Inav_mc_vel_z_i
and set VEL Dnav_mc_vel_z_d = 100
. Now the quad should be drifting up/down even slower. Raise VEL Dnav_mc_vel_z_d
to the edge of oscillations. -
Now raise VEL P
nav_mc_vel_z_p
to the edge of oscillations. Now ALTHOLD should be almost perfect. But if the copter is buzzing or slightly oscillating while ALTHOLD is active. You have the ALT_Pnav_mc_pos_z_p
set too high and/or VEL Pnav_mc_vel_z_p
is pushing too hard to reach the altitude target, which is causing some over-shoot. Start lower VEL Pnav_mc_vel_z_p
first. Then lower ALT_P if there is no change after a reduction of 20 points. -
And finally set
nav_mc_hover_thr
slightly higher/lower (50 - 100uS) than your actual hover throttle and tune VEL Inav_mc_vel_z_i
. The copter should be able to compensate.
What is the trick with VEL I nav_mc_vel_z_i
?
It is used to compensate for nav_mc_hover_thr
(hover throttle) being set to a slightly incorrect value. You can't set hover throttle to an exact value, there is always influence from thermals, battery charge level etc. Too much VEL I nav_mc_vel_z_i
will lead to vertical oscillations.
If its too low it can cause the copter to drop or jump when ALTHOLD is enabled. Very low VEL I nav_mc_vel_z_i
can result in total inability to maintain altitude.
The easiest trial and error testing method is done through the INAV OSD while in the field. Or by the Adjustments inflight tuning while in the air.
Climb rate is calculated using sensor data from the Accelerometer, Barometer and GNSS velocity NED/NEU. The average strength of these noisy signals are taken into account, to estimate the mean altitude. INAV sensor fusion weights are set by:
inav_w_z_baro_p = 0.350
- Weight LPF for barometer estimated altitude and climb rate.inav_w_z_baro_v = 0.100
- Weight LPF for barometer estimated climb rate measurement.inav_w_z_gps_p = 0.200
- Weight LPF for GPS altitude position. Vertical data is noisy and works better for airplanes than copter.inav_w_z_gps_v = 0.100
- Weight LPF for GPS climb rate velocity measurement.
Too high inav_w_z_baro_p
will make ALTHOLD nervous, and setting it too low will make it drift, so you risk running into the ground when cruising around. Using GNSS data for vertical velocity can allow you to lower the barometer weight to make ALTHOLD smoother without making it less accurate. But ONLY if your build consistently provides high GNSS sensor accuracy on every power-up.
These weights should only be adjusted if you have a firm grasp of their relationship. Small adjustments can make a significant difference, and has the potential to make things worse, if not tested under different atmospheric conditions.
Tuning Position Controller - XY axis:
Inability to obtain an accurate horizontal position can be caused by a number of reasons. These prerequisites below, MUST be resolved or achieved before attempting to tune the navigation POS, VEL and HEADING PID controller.
- 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. Possible causes
- Main stabilization PID_CD and LEVEL is poorly tuned. Or the Copter has a low thrust to weight ratio - Tune main stabilization PID's first.
- Poorly Installed, Aligned or Calibrated magnetometer (compass) - If a magnetometer is used, read here to provide the best results.
- High accelerometer vibrations from the motors, props or frame-resonance.
Tuning of copter XY axis is best performed on a day no colder than 10°C. This is due to the effect temperature has on the IMU.
When tuning the Nav XY controllers, you require a means to reference the copters target position, to its real-time turning or stopping position. Otherwise you are just guessing.
This is best done by logging flight controller data. And gauging the changes with one or all of the following software: MWP Tools , INAV Blackbox Explorer or Blackbox Tools.
Horizontal POS + VEL + HEADING PID Tuning:
The following settings can be accessed using the Configurator CLI or Tuning tab under Additional PID Gains. Or by the CMS OSD stick menu's.
- If the multicopters bank angle or speed is too high - Lowering the
nav_mc_bank_angle
andnav_auto_speed
will help to acquire the target position, especially when windy.
Position XY:
nav_mc_pos_xy_p
- Controls how fast the copter will fly towards the target position. This is a multiplier to convert the distance to the target velocity.
Velocity XY:
nav_mc_vel_xy_p
- Controls velocity to acceleration. Increasing the gain will provide a stronger response when position error occurs.nav_mc_vel_xy_i
- Increasing this gain can compensation for position drift, caused by the wind.nav_mc_vel_xy_d
- Increasing this gain can help smooth the P gain response, and lower the chance of target overshoot, up to a point.nav_mc_vel_xy_ff
- Attempts to predict velocity to acceleration disturbances via sensory input, to actively reduce the controllers response time.nav_mc_vel_xy_dterm_attenuation
- Attenuation of VEL_XY_D controller in %. Providing a smoother control response when the copter is navigating at speed. VEL_XY_D is not attenuated at low speeds, braking or accelerating. Some copters may react smoother with less attenuation applied.nav_mc_vel_xy_dterm_attenuation_start
- A point in percentage between the current horizontal velocity and the target, when VEL_XY_D attenuation begins.nav_mc_vel_xy_dterm_attenuation_end
- A point in percentage between the current horizontal velocity and the target, when VEL_XY_D attenuation reaches thenav_mc_vel_xy_dterm_attenuation
value.nav_mc_vel_xy_dterm_lpf_hz
- Low pass filter cutoff frequency for the VEL_XY_D controller. To allow for a smoother target response when traveling atnav_auto_speed
ornav_max_auto_speed
. The default cutoff is already low. However, even lowering it to 1, can still help on highly reactive copters.
Heading:
nav_mc_heading_p
- Controls the strength that the yaw axis will track the IMU's Compass derived heading target.
Setup Tuning Rangefinder Flow:
Hardware requirements:
To use the rangefinder capabilities of INAV you require two sensors - Lidar / Sonar, to measure distance to the surface. And Optical flow, to measure motion or flow across the terrain.
Tested sensors:
- Matek 3901-L0X Lidar & Optical-Flow board
- MicoAir MTF-01 Optical Flow & Lidar Sensor (prior to INAV 7.1.0)
Note: When powering-up and initializing the rangefinder hardware. Ensure the Lidar sensor has a distance between it and the ground, equivalent to 1/4 of the sensors minimum operation range, based on sensor specs.
Connecting and configuring the hardware:
Combination sensor boards are the easiest to setup. You only require one serial port to get the data from both sensors. i.e. Optical-flow and Lidar/sonar sensors.
Prerequisites:
- The copter has been flight tested in ANGLE and ALTHOLD, by just using the barometer and GNSS module. Before you attempt to use the Lidar & Optical flow sensors.
- You must align the arrow on the rangefinder board, so the optical flow sensor works in unity with the flight controllers accelerometer arrow. This step is equally as critical as getting the magnetometer alignment correct, for GNSS enabled flight.
Software configuration:
Once you have decided which serial port you will wire the sensors to. Go to the Configurator Ports Tab and select the MSP protocol at 115200 baud.
Then go to the Configuration Tab under Sensors & Buses and select MSP for RangeFinder and MSP for Optical-Flow
If you've connected and configured everything correctly. You should see the Sonar & Opflow sensors active
and ready (blue). If they have appeared in red. Plugged-in the flight battery for them to show as active. Or recheck the serial TX/RX wiring.
At bear minimum, you should have Gyro, Accelerometer, Barometer, Flow and Sonar active for the rangefinder to operate.
Aligning the hardware:
There isn't a GUI to align the optical flow sensor. However, you can use the Configurator Alignment Tool and make like the Optical flow sensor is a magnetometer, with some success. But it's still more beneficial to use the sensor output method to ensure the Optical flow is aligned correctly with the FC's accelerometer.
Go into CLI and set debug mode = FLOW_RAW
Find a location that is well-lit, preferably by natural light. With the ground surface providing good contrasting terrain:
-
Without a surface that has different contrast and texture, it can not measure motion. It will not work correctly/optimally on solid colors, low or repetitive surface texture, or in low light condition.
-
A Laser rangefinder needs a relatively reflective surface for best operation. Its operation distance will be reduced over dark surface.
Open the Configurator Sensors tab. Then lift the copter 40-70cm over the surface, and tilt it side to side on the roll, then fore and aft on the pitch axis. The max tilt should be around 30-40 degrees. The Optical flow lens should always be looking down at the surface. Make sure that you only tilt the copter on its central axis, without moving it across the terrain.
Observe the graphs and make sure Debug 0
(flow rate X) looks similar to Debug 2
(flow coordinates X).
And Debug 1
(flow rate Y) is similar to Debug 3
(flow coordinates Y).
If it doesn't look correct. Change the align_opflow
setting in CLI, then retry the procedure until your Debug 0
looks
similar to Debug 2
and Debug 1
is similar to Debug 3
.
Because the Optical Flow sensor is looking downwards [FLIP
is default], there are only 4 possible alignment angles: CW0FLIP
, CW90FLIP
, CW180FLIP
and CW270FLIP
.
[!Note] Those values are relative to the FC board, not the frame. So if your FC is mounted upside down, possible values can be
CW0
,CW90
,CW180
andCW270
, the opposite ofFLIP
being added.
Optical flow calibration:
Go to the Configurator and open the Calibration tab and follow the instructions for Optical Flow Calibration. You will have 30 seconds to tilt the quad in a way you did in "Aligning the hardware:" section.
For the Matek 3901-L0X board and other modules that use the PMW3901 flow sensor chip. The opflow_scale
value is generally between 9-10.
Flight modes:
There is no specific flight mode for Optical flow. From a flight modes perspective it’s the same as
POSHOLD mode when you use it with a GNSS module.
To enable terrain following altitude hold you need to enable SURFACE mode together with ALTHOLD or POSHOLD.
SURFACE mode works as a modifier for the altitude hold controller and alters its behavior to use altitude Above Ground Level (AGL) instead of altitude above launch point.
This image is only an example of how I use a rangefinder, together with a GNSS module for POSHOLD use, when the copter is above the workable altitude and position control range of the Lidar and Optical Flow sensors. You can however use POSHOLD at lower altitudes, together with the rangefinder surface mode, if you don't install a GNSS module into your copter.
Only enable inav_allow_dead_reckoning
if you do not have a GNSS module, for outside flight. Of if you do have one, and are flying indoors, with a slim chance of obtaining a GNSS 3D fix.
Do not arm the FC with rangefinder surface mode active. It can have undesirable results. Always arm in ANGLE mode.
Angle limits:
The copters bank angle in Surface mode is limited by -
max_angle_inclination_rll
max_angle_inclination_pit
It is not advisable to increase these setting beyond 38 degrees, due to the limited FOV both these sensors have.
This also applies to -
nav_mc_bank_angle
For use in POHOLD. But its value is also constrained by the max_angle_inclination
angles in the software.
Tuning:
The Rangefinder (surface) and Optical-flow (flow) gains should only be tuned after the XYZ navigation PID's are optimally tuned.
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.
Should be set approximately 20cm belownav_max_terrain_follow_alt
. When it's set to the sensors max. reliable working range.inav_w_z_surface_p
- Weight (cutoff frequency) for surface altitude applied to the Rangefinders estimated altitude. Setting is used when rangefinder is present, within its working distance above the ground. And/or Surface mode is enabled.inav_w_z_surface_v
- Weight (cutoff frequency) for surface velocity applied to the Rangefinders estimated climb rate. Setting is used when rangefinder is present, within its working distance above the ground. And/or Surface mode is enabled.
Optical-flow - Terrain motion sensor weights:
inav_w_xy_flow_p
- Optical flow sensor weight measurement for XY position. Also effected by light intensity.inav_w_xy_flow_v
- Optical flow sensor weight measurement for XY velocity. Also effected by light intensity and the texture of the terrain.inav_allow_dead_reckoning
- Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoor Optical Flow navigation
Both Lidar and optical flow offer more precise altitude and position accuracy, when comparing to a GNSS module and Barometer. So it's possible to tune Pos_XY, Vel_XY, Pos_Z and Vel_Z PIDs higher than defaults. Here are PID settings that were tested with success:
nav_mc_vel_z_p = 150
nav_mc_vel_z_i = 240
nav_mc_vel_z_d = 25
nav_mc_pos_xy_p = 80
nav_mc_vel_xy_p = 50
nav_mc_vel_xy_i = 40
nav_mc_vel_xy_d = 60
However keep in mind these setting should be tuned to optimally support all available sensors, unless you only intend to use Rangefinder / Optical-flow, and not GNSS / Barometer.
[!Note] The manufacturer specifications for their rangefinder modules should always be taken into account.
Optical flow sensors have a greater range limitation, than the Lidar altitude sensor they are coupled with. And most have a limited speed of operation around 7m/s max. With a required light intensity for reliable operation, greater than 60 Lux.
So you will often find the copters ability to hold position is lost before the Lidar sensors looses its ability to hold altitude.