Skip to content
breadoven edited this page Aug 21, 2020 · 78 revisions

This Wiki page needs updating in regards to renamed CLI variables.

This page will list and explain all the different navigational flight modes of iNav:

For safety reasons, iNAV’s navigation modes can be activated only if

  • ACC and MAG are calibrated properly,
  • you have a valid 3D GPS fix,
  • the FC is armed.

This applies to enabling the navigation modes in the Configurator as well as at the flying field.
(For bench tests without(!) propellers you may change “set nav_extra_arming_safety = ON” to “OFF” in CLI.)

  • Flightmodes are self contained. For example: with RTH and WP (Waypoints) it's not necessary to enable angle, althold or mag, it enables what it needs. Read more below in POSHOLD section.
POSHOLD WAYPOINT RTH ALTHOLD
ANGLE X X X
ALTHOLD X X X
MAG X X
BARO X X X

BE AWARE ON A FIXED WING THAT AUTO THROTTLE WILL CEASE AND THE MOTOR WILL STOP IN ALL NAV MODES EXCEPT NAV RTH AND NAV WP IF THE THROTTLE IS REDUCED BELOW THE MIN_CHECK SETTING.

Note: All iNAV parameters for distance, velocity, and acceleration are input in cm, cm/s and cm/s^2.

Let's have a look at each mode of operation in detail.

ALTHOLD - Altitude hold

When activated, the aircraft maintains its actual altitude unless changed by manual throttle input. Throttle input indicates climb or sink up to a predetermined maximum rate (see CLI variables). Using ALTHOLD with a multicopter, you need a barometer.
SONAR: Altitude hold code will use sonar automatically on low altitudes (< 3m) if hardware is available.
Using ALTHOLD with a plane (fixed wing: fw) with GPS: Since iNAV 1.5 it's recommended to keep baro enabled, and for iNav 1.6 the plan is to rely even less on GPS altitude when baro is enabled.

In general you shouldn't mix up ALTHOLD and ACRO/HORIZON: ALTHOLD doesn't account for extreme acro maneuvers.

Activate ALTHOLD by ALTHOLD flight mode.
Altitude, as calculated by iNAV's position estimator, is recorded to BLACKBOX as navPos[2].

a) Using ALTHOLD with a multicopter (mc):

Activate AIRMODE to keep the copter stable in fast descent - now you can do the whole flight in altitude hold - from take-off to landing.

Climb rate in ALTHOLD mode:
"set nav_max_climb_rate = 500" and "set nav_manual_climb_rate = 200" define the maximum climb and decent rate in autonomous/manual flight modes.
The neutral position of the throttle stick to hold current altitude is defined by

  • “set nav_use_midthr_for_althold=ON”: use mid position of throttle stick as neutral. By default the mid position value is typically 1500us as set in the "Receiver" tab.
  • “set nav_use_midthr_for_althold =OFF”: use current stick position (i.e. when activating ALTHOLD) as neutral. [Yet, if "nav_use_midthr_for_althold=OFF”, and you enable ALTHOLD with throttle stick too low (like on the ground) iNAV will take “thr_mid” as a safe default for neutral. “thr_mid” is defined in the “Receiver” tab and should be set to hover throttle.]

In the moment you engage ALTHOLD, iNAV always sends “nav_mc_hover_thr” to the motors as the starting value of the altitude control loop. You should configure this to your copter's hover setting, if your copter doesn't hover close to the default value of 1500us. Otherwise your copter will begin ALTHOLD with a jump or drop.

Example: Let's assume "nav_mc_hover_thr” is already set correctly to your copter's hover throttle and “set nav_use_midthr_for_althold =OFF”. Let's say you have your throttle stick at 30%, and you enter ALTHOLD, your copter will maintain hover at this 30%. If throttle is increased up to 40% it will start to climb. (Even if your copter needs 60% throttle to actually climb up in normal flight without ALTHOLD.)

It's important to note that when the battery is full, "nav_mc_hover_thr” could be a lower value than when the battery is weaker. With a weaker battery more throttle will be needed to maintain a hover. A practical way to establish an approximate valid value is to use the iNav OSD screen to test values real-time when in the field. Once an approximate "nav_mc_hover_thr” has been established, then adjust the PIDs as described in the "PIDs for altitude hold" section below.

"set alt_hold_deadband = 50": You have to change throttle command (e.g. move throttle stick) by at least this amount to make the copter climb or descend and change target altitude for ALTHOLD.
If ALTHOLD is activated at zero throttle iNAV will account for deadband and move the neutral "zero climb rate" position a little bit up to make sure you are able to descend.

PIDs for altitude hold:
The following values can be accessed using iNav OSD when configured for FPV from the "ALT MAG" screen within the "PIDS" section. Alternatively, the comparable variable, in parenthesis (), can be entered in the CLI of iNav Configurator.

  • 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_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_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.

Inability to maintain altitude can be caused by a number of reasons:

  1. insufficient ALT_P and/or ALT_I
  2. non-functional baro (please go to "Sensors" tab in Configurator and verify that baro graph changes as you move the quad up and down
  3. seriously underpowered quad (ALTHOLD is able to compensate only to some degree. If your quad hovers at 1700 linear throttle without any expo, ALTHOLD might fail to compensate)
  4. Gaining altitude during fast flight is likely due to increased air pressure and that is treated as going down in altitude - try covering your baro with (more) foam.

ALT+VEL PID Tuning
Let's make a small experiment: Make sure baro is well isolated. You may also want to reduce baro weight:

  • "set inav_w_z_baro_p = 0.5" and "set ALT P(nav_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 "VEL * (nav_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 I (nav_mc_vel_z_i)" and "set VEL D (nav_mc_vel_z_d) = 100". Now the quad should be drifting up/down even slower. Raise "VEL D (nav_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 (50-100) higher/lower than your actual hover throttle and tune "VEL I (nav_mc_vel_z_i)" until the quad is able to compensate.

Keep in mind that no tuning can fix bad baro isolation issue.

If quad is buzzing while ALTHOLD is activated try lowering "VEL P (nav_mc_vel_z_p)" a bit.

What is the trick with "VEL I (nav_mc_vel_z_i)"?
"VEL I (nav_mc_vel_z_i)" 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, too low "VEL I (nav_mc_vel_z_i)" 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_alt_p)", "VEL P (nav_mc_vel_p)", "ALT I (nav_auto_climb_rate)", and "nav_manual_climb_rate".

Climb rate is calculated from the readings of the accelerometer, barometer and – if available – from GPS (“set inav_use_gps_velned = ON”). How strongly the averages of these noisy signals are taken into account in the estimation of altitude change by iNAV is controlled by

  • set inav_w_z_baro_p = 0.350
  • set inav_w_z_gps_p = 0.200
    for vertical position (z) and
  • set inav_w_z_gps_v = 0.500
    for vertical velocity. Too high “inav_w_z_baro_p” will make ALTHOLD nervous, and too low will make it drift so you risk running into the ground when cruising around. Using GPS readings for vertical velocity allows for a lower weight for baro to make ALTHOLD smoother without making it less accurate.

// TODO: explain remaining relevant settings

b) Using ALTHOLD with an airplane (fixed wing, fw):

As for multicopters, iNAV is not intended to use ALTHOLD controller in anything but ANGLE mode.
iNAV controls pitch angle and throttle. It assumes that altitude is held (roughly) when pitch angle is zero. If plane has to climb, iNAV will also increase throttle. If plane has to dive, iNAV will reduce throttle and glide. The strength of this mixing is controlled by “nav_fw_pitch2thr”.
Set board alignment in such a way that your plane is flying level both in "MANUAL" and in "ANGLE", when you don't touch the sticks.

iNAV’s parameters for fixed wing:

  • set nav_fw_cruise_thr = 1400 # cruise throttle
  • set nav_fw_min_thr = 1200 # minimum throttle
  • set nav_fw_max_thr = 1700 # maximum throttle
  • set nav_fw_bank_angle = 20
  • set nav_fw_climb_angle = 20
  • set nav_fw_dive_angle = 15
  • set nav_fw_pitch2thr = 10 # pitch to throttle
  • set nav_fw_roll2pitch = 75 # roll to pitch
  • set nav_fw_loiter_radius = 5000

NAV POSHOLD - Position hold

For multirotor it will hold 3D position, throttle is automatic (AH). You can use your roll and pitch stick to move around. The position hold will be resumed when you center the roll/pitch stick again. You can also enable HEADING HOLD at the same time to lock the heading.

For fixed wing it will loiter in circles which radius is defined by the nav_fw_loiter_radius variable. The throttle is automatic. The altitude is controlled with the pitch stick (AH).

Always check POSHOLD working correctly, before you use RTH or start a WP mission.

Hints for safe operation:

  • Activate without props installed to check for reasonable operation.
  • When misconfigured, this mode can result in dramatic failure to hold position. Attitude (yaw & motion) inputs can/will result in rapid and unexpected motion.

NAV CRUISE - Fixed Wing Heading Hold

When enabled the machine will try to maintain the current heading and compensate for any external disturbances (2D CRUISE). User can adjust the flight direction directly with ROLL stick or with the YAW stick ( nav_fw_cruise_yaw_rate set the yawing rate at full stick deflection ). The latter will offer a smoother way to adjust the flight direction. If the mode is enabled in conjunction with NAV ALTHOLD also the current altitude will be maintained (3D CRUISE). Altitude can be adjusted, as usual, via the pitch stick. Both 2D/3D CRUISE modes forces ANGLE mode to be active so the plane will auto level.

RTH - Return to home

RTH will attempt to bring copter/plane to launch position. Launch position is defined as a point where aircraft was armed. RTH will control both position and altitude. You will have to manually control altitude if your aircraft does not have an altitude sensor (barometer).

With default settings RTH will land immediately if you are closer than 5 meters from launch position. If further away it will make sure to have at least 10 meters of altitude, then start going home at 3m/s, and land. It will disarm itself if so configured, otherwise you will have to manually disarm once on the ground.

There are many different modes for Altitude, see further down on this page

Activated by RTH flight mode.

WP - Autonomous waypoint mission

Autonomous waypoints are used to let the quad/plane autonomous fly a predefined mission. The mission is defined with waypoints, which have the information about latitude, longitude, height and speed between the waypoints. GUIs such as EZ-GUI, Mission Planner for iNav, Mobile Flight and mwp can be used to set the waypoints and upload the mission as well as store missions locally for reuse (exgui, mp4iNav, mwp at least). The iNav configurator has limited capability to create waypoint missions. Uploaded missions are saved in the FC until a reboot or a new uploaded mission erases the old one. Missions may also be saved to EEPROM, which survives reboot.

Once the waypoint mode is activated (NAV WP has to be set previously in the mode tabs to a specific switch/value), the quad/plane will start to fly the waypoint mission based upon the waypoints in numerical order. Waypoint missions can be restarted by switching NAV WP off/on; interruption during the mission is also possible with switching NAV WP off.

Currently up to 30 waypoints can be set on F1 boards, and 60 on F3 and better.

There is an additional wiki page further describing way point missions, tools and telemetry options.

// TODO: Explain better. // TODO: explain what happens when you are in WP mode and GPS fails.

GCS_NAV - Ground control station

This mode is just an permission for GCS to change position hold coordinates and the altitude. So it's not a flight mode itself, and needs to be combined with other flight modes.

In order to let the GCS have full control over the aircraft the following modes must be activated: NAV POSHOLD NAV ALTHOLD MAG TOGETHER with GCS_NAV.

This can be combined in whichever way you want to permit, e.g manual yawing or altitude control.

Keep in mind that if NAV POSHOLD is not combined with this mode you must combine ANGLE as the other modes are best combined with ANGLE mode.

// TODO: explain what happens when you are in GSC NAV mode and GPS fails.

right (roll/pitch) stick

Mode switch diagram

A diagram to indicate flight modes relation to navigation modes and illustrate sensor requirements:

RTH Altitude control modes

RTH sequence can control altitude in several different ways, controlled by nav_rth_alt_mode and nav_rth_altitude (the altitude in centimeters) parameters.

Default setting is NAV_RTH_AT_LEAST_ALT - climb to preconfigured altitude if below, stay at current altitude if above.

Maintain current altitude (NAV_RTH_NO_ALT)

nav_rth_alt_mode = CURRENT

nav_rth_altitude is ignored

Maintain current altitude + predefined safety margin (NAV_RTH_EXTRA_ALT)

nav_rth_alt_mode = EXTRA

nav_rth_altitude defines extra altitude margin

Predefined altitude (NAV_RTH_CONST_ALT)

nav_rth_alt_mode = FIXED

nav_rth_altitude defines exact RTH altitude above launch point.

If the multirotor is below nav_rth_altitude it will enter position hold and climb to desired altitude prior to flying back home. If the machine is above the desired altitude, it will turn and fly home and descend on the way.

Predefined altitude linear descent (AT_LEAST_LINEAR_DESCENT)

nav_rth_alt_mode = AT_LEAST_LINEAR_DESCENT

nav_rth_altitude defines exact RTH altitude above launch point. Aircraft will descend in a way that it'll reach the nav_rth_altitude altitude only when it reaches the home point. So aircraft can save energy by doing an easy descend on it's way back home.

If the aircraft is below nav_rth_altitude it will climb to desired altitude prior to flying back home. If the machine is above the desired altitude, it will turn and fly home, and descend on the way (on a linear straight line).

Maximum altitude since launch (NAV_RTH_MAX_ALT)

nav_rth_alt_mode = MAX

nav_rth_altitude is ignored

At least predefined altitude above launch point (NAV_RTH_AT_LEAST_ALT)

nav_rth_alt_mode = AT_LEAST

nav_rth_altitude defines exact RTH altitude above launch point

WIKI TOPICS

Wiki Home Page

INAV Version 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

Mixer Tab
Custom mixes for exotic setups
DevDocs Mixer.md

Outputs

DevDocs ESC and servo outputs.md
DevDocs Servo.md

Modes

Modes
Navigation modes
Navigation Mode: Return to Home
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md

Configuration

Sensor auto detect and hardware failure detection

Failsafe

Failsafe
DevDocs Failsafe.md

PID Tuning

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

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

Advanced Tuning

Fixed Wing Autolaunch
DevDocs INAV_Autolaunch.pdf

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

Clone this wiki locally