1 **REFER TO THIS PAGE FOR NAVIGATION MODES:** [Navigation-modes](https://github.com/iNavFlight/inav/wiki/Navigation-modes)
3 # Non-navigation modes index:
5 - [AIR MODE](#air-mode)
8 - [AUTOLEVEL](#autolevel-fw)
9 - [AUTOTUNE](#autotune-fw)
11 - [BLACKBOX](#blackbox)
14 - [FAILSAFE](#failsafe)
15 - [FLAPERON](#flaperon-fw)
17 - [HEADADJ](#headadj-mc)
18 - [HEADFREE](#headfree-mc)
19 - [HEADING HOLD](#heading-hold)
20 - [HOME RESET](#home-reset)
25 - [LOITER CHANGE](#loiter-change-fw)
26 - [MANUAL](#manual-fw) (called PASSTHROUGH mode up to version 1.8.1)
27 - [MC BRAKING](#mc-braking-mc)
29 - [NAV LAUNCH](#nav-launch-fw)
33 - [SERVO AUTOTRIM](#servo-autotrim-fw)
34 - [SOARING](#soaring-fw)
36 - [TELEMETRY](#telemetry)
37 - [TURN ASSIST](#turn-assist)
38 - [TURTLE](#turtle-mc)
41 ## Default flight mode ( No mode selected )
43 The default flight mode does not self level the aircraft around the roll and the pitch axes. That is, the aircraft does not level on its own if you center the pitch and roll sticks on the radio. Rather, they work just like the yaw axis: the rate of rotation of each axis is controlled directly by the related stick on the radio, and by leaving them centered the flight controller will just try to keep the aircraft in whatever orientation it's in. This default mode is called "Acro" mode (from "acrobatic", shown in the OSD as `ACRO`). It is also sometimes called "rate" mode because the sticks control the rates of rotation of the aircraft around each of the three axes. "Acro" mode is active whenever auto-leveled mode is enabled.
48 The following indicate if a mode is specific to a particular craft type:
55 In the standard mixer / mode, when the roll, pitch and yaw gets calculated and saturates a motor, all motors
56 will be reduced equally. When motor goes below minimum it gets clipped off.
57 Say you had your throttle just above minimum and tried to pull a quick roll - since two motors can't go
58 any lower, you essentially get half the power (half of your PID gain).
59 If your inputs would asked for more than 100% difference between the high and low motors, the low motors
60 would get clipped, breaking the symmetry of the motor balance by unevenly reducing the gain.
61 Airmode will enable full PID correction during zero throttle and give you ability for nice zero throttle
62 gliding and aerobatics. But also the cornering / turns will be much tighter now as there is always maximum
63 possible correction performed. Airmode can also be enabled to work at all times by always putting it on the
64 same switch like your arm switch or you can enable/disable it in air. Additional things and benefits: Airmode
65 will additionally fully enable Iterm at zero throttle. Note that there is still some protection on the ground
66 when throttle zeroed (below min_check) and roll/pitch sticks centered. This is a basic protection to limit
67 motors spooling up on the ground. Also the Iterm will be reset above 70% of stick input in acro mode to prevent
68 quick Iterm windups during finishes of rolls and flips, which will provide much cleaner and more natural stops
69 of flips and rolls what again opens the ability to have higher I gains for some.
73 In this auto-leveled mode the roll and pitch channels control the angle between the relevant axis and the vertical, achieving leveled flight just by leaving the sticks centered.
74 Maximum banking angle is limited by `max_angle_inclination_rll` and `max_angle_inclination_pit`
78 The altitude of the aircraft a the moment you activate this mode is fixed.
82 AUTOLEVEL will attempt to automatically tune the pitch offset (`fw_level_pitch_trim`) a fixed-wing airplane needs to not lose altitude when flying straight in ANGLE mode.
84 The new value isn't saved to EEPROM, you have to save it manually using either the configurator or a [stick combo](https://github.com/iNavFlight/inav/blob/master/docs/Controls.md).
88 For detailed description go to https://github.com/iNavFlight/inav/wiki/Tune-INAV-PIFF-controller-for-fixedwing
90 AUTOTUNE will attempt to tune roll and pitch P, I and FF gains on a fixed-wing airplane.
92 Autotune will monitor behavior of the airplane when you fly it and adjust P, I and FF gains to reach optimal performance.
96 Take off. Any manual flight mode will do, ACRO is the best option. Enable AUTOTUNE mode. Do hard maneuvers on each axis separately. For roll - bank hard left/hard right. For pitch - fast climb, steep dive. Initially you probably will notice very soft response - make sure your flying field is big enough for slow turns.
98 The more maneuvers you will do - the better results AUTOTUNE will be able to reach.
100 AUTOTUNE will adjust gains constantly but it will take a snapshot of current gains every 5 seconds. When you disable AUTOTUNE gains from last snapshot will be restored. If you turn AUTOTUNE on and off before 5 seconds elapse - PIFF gains won't be changed.
102 Currently AUTOTUNE don't save gains to EEPROM - you have to save manually, using a [stick combo](https://github.com/iNavFlight/inav/blob/master/docs/Controls.md).
106 Make the beeper connected to the FC beep (lost model finder).
110 If you're recording to an onboard flash chip, you probably want to disable Blackbox recording when not required in order to save storage space. To do this, you can add a Blackbox flight mode to one of your AUX channels on the Configurator's modes tab. Once you've added a mode, Blackbox will only log flight data when the mode is active.
112 A log header will always be recorded at arming time, even if logging is paused. You can freely pause and resume logging while in flight.
114 See [`BLACKBOX`](/iNavFlight/inav/blob/master/docs/Blackbox.md) for more information
118 Enables the servo gimbal
122 Lets you activate flight controller failsafe with an aux channel.
123 Read [Failsafe page](https://github.com/iNavFlight/inav/wiki/Failsafe) for more info.
127 Activating it moves both ailerons down (or up) by predefined offset.
129 Configuration besides activating FLAPERON mode is pretty simple, and consists of just one CLI variable:
130 - `flaperon_throw_offset` defines throw range in us for both ailerons that will be applied when FLAPERON mode is activated. By default it 250 with max at 400.
132 Flaperon offset is by default is applied as a servo mixer input with ID=14 so using custom servo mixing you can configure FLAPERON mode to deflect any servos you need (including dedicated flaps).
136 It allows you to set a new yaw origin for HEADFREE mode.
140 In this mode, the "head" of the multicopter is always pointing to the same direction as when the feature was activated. This means that when the multicopter rotates around the Z axis (yaw), the controls will always respond according the same "head" direction.
142 With this mode it is easier to control the multicopter, even fly it with the physical head towards you since the controls always respond the same. This is a friendly mode to new users of multicopters and can prevent losing the control when you don't know the head direction.
146 This flight mode affects only yaw axis and can be enabled together with any other flight mode.
147 It helps to maintain current heading without pilots input and can be used with and without magnetometer support. When yaw stick is neutral position, Heading Hold mode tries to keep heading (azimuth if compass sensor is available) at a defined direction. When pilot moves yaw stick, Heading Hold is temporary disabled and is waiting for a new setpoint.
149 Heading hold only uses yaw control (rudder) so it won't work on a flying wing which has no rudder.
153 This hybrid mode works exactly like the previous ANGLE mode with centered roll and pitch sticks (thus enabling auto-leveled flight), then gradually behaves more and more like the default RATE mode as the sticks are moved away from the center position. Which means it has no limitation on banking angle and can do flips.
157 Turns off the RGB LEDs
159 ### LOITER CHANGE (FW)
161 Reverses set loiter direction when mode selected.
165 Direct servo control in fixed-wing. This mode was called PASSTHROUGH mode up to version 1.8.1.
167 In this mode there is no stabilization. Please note that MANUAL mode also overrides nav modes except RTH. To switch to a nav mode such as POSHOLD from MANUAL, MANUAL needs to be turned off first.
169 What FC does in MANUAL mode is: Motor mixing, Servo Mixing, Expo settings, Throws limiting (see the `manual_*_rate` settings). Note that Failsafe is still active in this mode and can override the controls.
177 Airplane launch assistant
179 This flight mode is intended to provide assistance for launching the fixed-wing UAVs. Launch detection works by monitoring airplane acceleration - once it breaches the threshold for a certain amount of time launch sequence is started.
181 Gliders have different needs than motorized planes. See below for note on glider launch setup.
183 The entire time `NAV LAUNCH` mode it will try and stabilize plane, it will target zero roll, zero yaw and predefined climb angle. The I-gain of the PIFF regulator is also disabled to prevent I-gain growing during launch until motor is started. When successful launch is detected it waits for preconfigured amount of time before starting motor.
185 `NAV LAUNCH` is automatically aborted after 5 seconds or by any pilot input on PITCH/ROLL stick. When it has aborted it goes to whichever selected mode, which can be Angle, Rate, Horizon, RTH or a waypoint mission (if no other mode is selected it will go to Rate mode).
187 It's safe to keep it activated the `NAV LAUNCH` mode during flight after the launch has being completed. Keep in mind that if you accidentally disarm while flying you need to disable `NAV LAUNCH` mode to being able to control the model again.
189 See INAV CLI for all available adjustable parameters, they start with `nav_fw_launch_`
191 Sequence for launching airplane using `NAV LAUNCH` mode looks like this:
193 1. Set switch to `NAV LAUNCH` mode prior to arming (note that it won't actually enable until arming)
194 1. ARM the plane. Motor should start spinning at min_throttle (if `MOTOR_STOP` is active, motor won't spin)
195 1. Put throttle stick to desired throttle value to be set **after** launch is finished. Motor should start spinning with `nav_fw_launch_idle_thr`. Default is 1000 so it will respect `MOTOR_STOP` if active. Verify that motor doesn't respond to throttle stick motion. Don't touch the pitch/roll stick! From version 3.0 `nav_fw_launch_idle_motor_delay` can be set to delay the motor starting at idle (useful for launching large aircraft). When idle motor delay is used the launch beep sound changes a few seconds before the motor is about to start as a warning to the pilot (beep becomes more rapid).
196 1. Throw the airplane. It must be thrown leveled, or thrown by slinging it by wingtip.
197 1. Motors will start at pre-configured `nav_fw_launch_thr` (default 1700) after `nav_fw_launch_motor_delay` (500ms)
198 1. Launch sequence will finish when pilot switch off the NAV LAUNCH mode or move the sticks.
200 If it won't detect launch it's possible that you need to lower your threshold. Look at the CLI variables.
202 CAUTION: Motors will spin if you unset `NAV LAUNCH` mode after arming.
204 From version 1.9 `NAV LAUNCH` can be permanently enabled via the configurator or the CLI using `feature FW_LAUNCH` in this case `NAV LAUNCH` doesn't need to be enabled via a transmitter switch prior to arming.
205 If you want to launch the plane manually just move pitch/roll stick after you have armed the plane and you have back throttle control.
206 If you inadvertedly disarm mid-air before raising the throttle again (you should lower the throttle to arm again) move pitch/roll stick and you will have throttle control back.
208 **GLIDER / SLOPER SETUP**
210 For obtaining launch assistance for hand-thrown gliders, it's a bit tricky. One possible solution is to setup the throttle as in input for switching modes. At lowest throttle setting, disarm and enter passthru. Just above minimal throttle, turn on Nav Launch, then just above that, Arm and activate Angle - all simultaneously "on" for launch.
212 This will allow the FC to reset the launch sequence and be ready for toss with Angle activated after launch.
214 Setup launch parameters appropriately:
216 `nav_fw_launch_climb_angle = XX 45?`
218 (Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit)
220 `set nav_fw_launch_thr = 1700`
222 ^^this command for a glider can be problematic. Not obvious, since Airplanes change PID values for throttle based on `set tpa_rate = XXX` and `set tpa_breakpoint = XXXX` (adjust accordingly). Also, not well documented but PIDs are boosted at low throttles by 1.5X!! Can cause unexplained behavior at launch. For some gliders - having PID gains reduced for toss is beneficial (DLG launch may be fastest speed the glider travels)
224 `nav_fw_launch_velocity = XXX 300?`
226 (Forward velocity threshold for swing-launch detection [cm/s])
228 One option is to add Horizon mode at very top end of throttle, to enable acro flying with ability to drop back to angle mode for emergency recovery.
232 Switches to the different alternative OSD displays ALT1, ALT2 or ALT3. The default OSD is shown when none of these are selected.
236 Switches off the OSD.
238 ### SERVO AUTOTRIM (FW)
239 In flight adjustment of servo midpoint for straight flight
241 This was changed in 3.0. Only servos with a "stabilized" rule on the INC Servo Mixer are trimmed. Also note that the automatic version of this introduced in 3.0 requires a GPS and detectable motion in order to work.
243 _The purpose of this mode is to set new midpoints for servos 2 to 5. Makes sure you assign these servo numbers to your control surfaces or they will not be trimmed. If you have another servo (e.g. a servo gimbal) assigned to to servos 2 to 5, then this servo _will_ be trimmed._
245 This is so when switching into manual mode the plane will fly straight, its also to help the PIFF controller know where the plane is expected to fly straight.
249 1. This is intended to use in air.
250 2. Fly straight, choose what mode that suites you best. (`manual`, `angle` or `acro`)
251 3. Enable `SERVO AUTOTRIM` mode, and keep flying straight for 2 seconds. After 2 seconds it will set new midpoints based on average servo position during those 2 seconds.
252 4. If you're are NOT happy with new midpoints disable `SERVO AUTOTRIM` mode and it will revert back to old settings. If you want to keep new midpoints keep `SERVO AUTOTRIM` turned on, land aircraft and disarm. New midpoints will be saved.
254 You may want to inspect your new midpoints after landing, if the servo offset is a lot you may alter your linkage mechanically and redo servo midpoint.
256 This is not to be confused with tuning your aircraft for leveled flight in `ANGLE` mode, to do this you need to adjust your board alignment so straight flight for that aircraft is show the board being level ( 0 pitch and 0 roll ).
260 Fixed wing mode for soaring flight with motor off so intended for sailplanes or motor gliders. Mode becomes active only when Position Hold or Cruise/Course Hold modes are also selected providing semi-autonomous soaring whilst circling or flying straight with heading hold.
262 When mode is active altitude control is disabled and Angle mode allowed to free float (disabled) within the pitch range set by `nav_fw_soaring_pitch_deadband` (float pitch angle either side of level). The motor can be stopped by setting `nav_fw_soaring_motor_stop`.
266 Enable terrain following when you have a rangefinder enabled
270 Normally YAW stick makes a turn around a vertical axis of the craft - this is why when you fly forward in RATE and do a 180-deg turn using only YAW you'll end up looking upwards and flying backwards. In ANGLE mode this also causes an effect known as a pirouetting where turn is not smooth the horizon line is not maintained.
272 In RATE mode pilot compensated for this effect by using both ROLL and YAW sticks to coordinate the rotation and keep attitude (horizon line).
274 TURN ASSISTANT mode calculates this additional ROLL command required to maintain a coordinated YAW turn effectively making YAW stick turn the aircraft around vertical axis relative to the ground.
276 In RATE mode it allows one to makes a perfect yaw-stick only turn without changing attitude of the machine. There might be slight drift due to not instant response of PID control, but still much easier to pilot for a RATE-mode beginners.
278 In ANGLE mode it also makes yaw turns smoother and completely pirouette-less. This is because TURN ASSIST introduces feed-forward control in pitch/roll and maintains attitude naturally and without delay.
280 From INAV 1.7 turn assist will work one planes, copy paste from pull request:
282 This extends TURN_ASSIST flight mode on airplanes - when doing a turn on an airplane it will calculate required yaw and pitch rate to keep airplane pointed at horizon.
284 TAS (from airspeed sensor) will be used for calculation if available - otherwise code will use cruise airspeed defined by fw_reference_airspeed.
288 Provides a means of flipping a multicopter that has "landed" upside down.
292 ## AUXILIARY CONFIGURATION
294 Spare auxiliary receiver channels can be used to enable/disable modes. Some modes can only be enabled this way.
296 Configure your transmitter so that switches or dials (potentiometers) send channel data on channels 5 and upwards (the first 4 channels are usually occupied by the throttle, aileron, rudder, and elevator channels).
298 _e.g. You can configure a 3 position switch to send 1000 when the switch is low, 1500 when the switch is in the middle and 2000 when the switch is high._
300 Configure your TX/RX channel limits to use values between 1000 and 2000. The range used by mode ranges is fixed to 900 to 2100.
302 When a channel is within a specified range the corresponding mode is enabled.
304 Use the GUI configuration tool to allow easy configuration when channel.
308 There is a CLI command, `aux` that allows auxiliary configuration. It takes 5 arguments as follows:
310 * AUD range slot number (0 - 39)
311 * mode id (see mode list below)
312 * AUX channel index (AUX1 = 0, AUX2 = 1,... etc)
313 * low position, from 900 to 2100. Should be a multiple of 25.
314 * high position, from 900 to 2100. Should be a multiple of 25.
316 If the low and high position are the same then the values are ignored.
320 Configure AUX range slot 0 to enable ARM when AUX1 is within 1700 and 2100.
326 You can display the AUX configuration by using the `aux` command with no arguments.
357 * "SERVO AUTOTRIM" 37
359 * "CAMERA CONTROL 1" 39
360 * "CAMERA CONTROL 2" 40
361 * "CAMERA CONTROL 3" 41
365 * "NAV COURSE HOLD" 45
370 * "MSP RC OVERRIDE" 50