-
Notifications
You must be signed in to change notification settings - Fork 1.6k
Navigation PID tuning (MC)
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.
Note
There is also a companion wiki page, that is essential reading beforehand. The Installation location, Setup and Calibration of the GNSS/Magnetometer module, to providing the best navigation performance achievable, is absolutely essential GPS and Compass setup. Accounting for this detail can make your build a great success, or not so much.
Inability to maintain altitude can be caused by a number of reasons:
- Insufficient ALT_P and/or ALT_I
- 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.
- 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.
Keep in mind that tuning cannot fix:
- Bad barometer isolation
- Poor GNSS precision - See here
- High accelerometer vibrations from the motors or props.
Make sure these hardware conditions are addressed first, before you even attempt to tune the nav PID's.
The following values can be accessed using the Configurator CLI or PID Tuning tab. Or by the CMS OSD stick menu's.
Altitude is always 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 copter will add to achieve desired acceleration - VEL I
nav_mc_vel_z_i
- controls compensation for hover throttle (and vertical air movement, thermals). This can essentially be zero if hover throttle is precisely 1500us. Too much VEL I will lead to vertical oscillations, too low VEL I will cause drops or jumps when ALTHOLD is switched on. - VEL D
nav_mc_vel_z_d
- acts as a dampener for VEL P and VEL I, will slower the response and reduce oscillations from too high VEL P and VEL I
If ALT P nav_mc_pos_z_p
and ALT I nav_mc_auto_climb_rate
have been set to zero (0) during the PID adjustments, setting ALT P nav_mc_pos_z_p
to a non-zero value (>100), will have the effect of changing the ALTHOLD altitude using the throttle. Once again, the easiest trial and error testing is done through the INAV OSD while in the field. Or inflight tuning while in the air.
Try a small experiment: Make sure the barometer is well isolated. You may also want to reduce baro weight. With this ideally being performed on a day no colder than 10°C.
-
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 -
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.
If copter is buzzing or slightly oscillating while ALTHOLD is active in any navigation mode, try lowering VEL P nav_mc_vel_z_p
a bit.
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 will cause drops or jumps when ALTHOLD is enabled. Very low VEL I nav_mc_vel_z_i
can result in total inability to maintain altitude.
To deal with oscillations you can try lowering your ALT P nav_mc_pos_z_p
, VEL P nav_mc_vel_z_p
, and/or "ALT I nav_mc_auto_climb_rate
, and nav_mc_manual_climb_rate
.
Climb rate is calculated from the readings of the accelerometer, barometer and from GNSS velocity NED. The average strength of these noisy signals are taken into account, to estimate the mean altitude. Fusion filter weights in INAV are set by:
inav_w_z_baro_p = 0.350
inav_w_z_gps_p = 0.200
-
inav_w_z_gps_v = 0.100
for vertical (z) position and velocity.
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 allows for a lower barometer weight to make ALTHOLD smoother without making it less accurate.
These weights should only be adjusted if you have a firm grasp of their relationship. Small adjustment can cause a large changes. Which can make things worse, if not tested under many atmospheric condition.
Still to come.
Still to come.
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
Outputs
DevDocs ESC and servo outputs.md
DevDocs Servo.md
Modes
Modes
Navigation modes
Navigation Mode: Return to Home
FW Launch Mode
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md
Configuration
Failsafe
Failsafe
DevDocs Failsafe.md
PID Tuning
Navigation PID tuning (FW)
Navigation PID tuning (MC)
EZ-Tune
PID Attenuation and scaling
Fixed Wing Tuning for INAV 3.0
Tune INAV PIFF 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
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 Tuning
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
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
UAV Interconnect Bus
Ublox 3.01 firmware and Galileo
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
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md