Updated Lightweight Telemetry (LTM) (markdown)
[inav.wiki.git] / Modes.md
blob75b3cbba21b9b36b28786462c6cd2426d36d14fc
1 # Introduction
2 Flight Modes in INAV can be categorized into two groups:
3 * **Navigation-Modes** which involve GPS and other positional sensors. Refer to the [Navigation-Modes](https://github.com/iNavFlight/inav/wiki/Navigation-modes) page for more information.
4 * **Non-Navigation-Modes** perform actions that may rely on a sensor like the gyro or no sensor at all. See the mode descriptions below.
6 Some modes are only available to certain craft types. This is indicated by:
7 * **FW** = Fixed Wing
8 * **MC** = Multi-Copter
10 Scroll down to the [AUXILIARY CONFIGURATION](#AUXILIARY-CONFIGURATION) section for how Modes are assigned to channels on your radio.
12 # Non-Navigation Modes Index:
14 - [ACRO MODE](#acro-mode) (default mode)
15 - [AIR MODE](#air-mode)
16 - [ANGLE](#angle)
17 - [ANGLE HOLD](#angle-hold-fw) **FW** (7.1 and later)
18 - [ARM](#arm)
19 - [ALTHOLD](#althold)
20 - [AUTO LEVEL TRIM](#auto-level-trim-fw) **FW**
21 - [AUTOTUNE](#autotune-fw) **FW**
22 - [BEEPER](#BEEPER)
23 - [BEEPER MUTE](#BEEPER-MUTE)
24 - [BLACKBOX](#blackbox)
25 - [CAMERA CONTROL](#camera-control)
26 - [CAMSTAB](#CAMSTAB)
27 - [FAILSAFE](#failsafe)
28 - [FLAPERON](#flaperon-fw) **FW**
29 - [FPV ANGLE MIX](#FPV-ANGLE-MIX-mc) **MC**
30 - [HEADADJ](#headadj-mc) **MC**
31 - [HEADFREE](#headfree-mc) **MC**
32 - [HEADING HOLD](#heading-hold)
33 - [HOME RESET](#home-reset)
34 - [HORIZON](#horizon)
35 - [KILLSWITCH](#killswitch)
36 - [LEDLOW](#ledlow)
37 - [LOITER CHANGE](#loiter-change-fw) **FW**
38 - [MANUAL](#manual-fw) **FW** (PASSTHROUGH v1.8.1 & earlier)
39 - [MC BRAKING](#mc-braking-mc) **MC**
40 - [MIXER PROFILE 2](#mixer-profile-2)
41 - [MIXER TRANSITION](#mixer-transition)
42 - [MSP RC OVERRIDE](#msp-rc-override)
43 - [MULTI FUNCTION](#multi-function) 
44 - [NAV LAUNCH](#nav-launch-fw) **FW**
45 - [OSD ALT](#osd-alt)
46 - [OSD SW](#osd-sw)
47 - [PREARM](#prearm)
48 - [SERVO AUTOTRIM](#servo-autotrim-fw) **FW**
49 - [SOARING](#soaring-fw) **FW**
50 - [SURFACE](#surface)
51 - [TELEMETRY](#telemetry)
52 - [TURN ASSIST](#turn-assist)
53 - [TURTLE](#turtle-mc) **MC**
54 - [USER1 & USER2 & USER3 & USER4](#USER)  (aka PinIO)
55 - [WAYPOINT PLANNER](#WP-Planner)
57 ### ACRO MODE
58 NOTE: This is **default** flight mode. It is only active when no other mode is active. There is no mode selection for ACRO in the configurator, only an ACRO box that highlights when no other mode is active.
60 This 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.
62 ### AIR MODE
64 In the standard mixer / mode, when the roll, pitch and yaw gets calculated and saturates a motor, all motors
65 will be reduced equally. When motor goes below minimum it gets clipped off.
66 Say you had your throttle just above minimum and tried to pull a quick roll - since two motors can't go
67 any lower, you essentially get half the power (half of your PID gain).
68 If your inputs would asked for more than 100% difference between the high and low motors, the low motors
69 would get clipped, breaking the symmetry of the motor balance by unevenly reducing the gain.
70 Airmode will enable full PID correction during zero throttle and give you ability for nice zero throttle
71 gliding and aerobatics. But also the cornering / turns will be much tighter now as there is always maximum
72 possible correction performed. Airmode can also be enabled to work at all times by always putting it on the
73 same switch like your arm switch or you can enable/disable it in air. Additional things and benefits: Airmode
74 will additionally fully enable Iterm at zero throttle. Note that there is still some protection on the ground
75 when throttle zeroed (below min_check) and roll/pitch sticks centered. This is a basic protection to limit
76 motors spooling up on the ground. Also the Iterm will be reset above 70% of stick input in acro mode to prevent
77 quick i-term windups during finishes of rolls and flips, which will provide much cleaner and more natural stops
78 of flips and rolls what again opens the ability to have higher I gains for some.
80 ### ANGLE
82 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.
83 Maximum banking angle is limited by `max_angle_inclination_rll` and `max_angle_inclination_pit`
85 ### ANGLE HOLD (FW)
87 This mode is a simple version of an attitude lock stabilizer. But its not designed for 3D aerobatic use.
88 It behaves more like Acro mode, in the way the desired flight attitude is achieved by stick deflection, and you release the stick to center. But the difference is, ANGLE HOLD will attempt to _hold or lock_ the pitch or roll attitude the airplane was commanded, when the stick is released back to center. Thus resisting any long term change to the flight attitude caused by the effects of wind...
89 Returning the airplane to level flight is done the same as when flying in Acro or Manual modes.
91 This flight mode has angle constraints set by the navigation angle limits - `nav_fw_climb_angle`, `nav_fw_dive_angle` and `nav_fw_bank_angle`. Which may also make it feel a little like ANGLE mode, with its bank limits.
93 It was designed to work with a flight mode and a modifier - `COURSE HOLD` or `ALT HOLD`. Although both **can not** be selected for use with ANGLE HOLD at the same time.
95 * ANGLE HOLD + COURSE HOLD - Will maintain a constant heading and climb angle over a long distance. e.g. Up or Down the side of a long mountain range.
96 * ANGLE HOLD + ALT HOLD - Will allow the airplane to make a long banking turn, without losing altitude in the turn.
99 **Use caution! - If the pilot requests the airplane to hold a high climb angle. The pilot MUST provide adequate throttle (motor thrust) to maintain airspeed or the airplane will stall.**
101 ### ARM
102 Activates the flight controller to be ready for flight.
104 ### ALTHOLD
106 Maintain the altitude of the aircraft a the moment you activate this mode is fixed. Find more information [here](https://github.com/iNavFlight/inav/wiki/Navigation-modes#althold---altitude-hold).
108 ### AUTO LEVEL TRIM (FW)
109 _Tuning mode_
111 AUTO LEVEL TRIM 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 a self levelling flight mode. To use AUTO LEVEL you should first be in a self levelling flight mode which does _not_ use ALTHOLD. ANGLE, HORIZON, and COURSE HOLD are all fine. Once in that mode, enable AUTO LEVEL and do not make corrections. AUTO LEVEL will attempt to tune the correct Angle of Attack for your current speed. You can see how level the craft is flying with the numerical variometer element on the OSD. +/- 0.3° is an acceptable tolerance. Once flying level, you can disable AUTO LEVEL. From INAV 6.0, a system message is shown when AUTO LEVEL is active. The trimming speed and accuracy can also be adjusted via [fw_level_pitch_gain](https://github.com/iNavFlight/inav/blob/master/docs/Settings.md#fw_level_pitch_gain). 
113 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). However, if you have a feature enabled which saves on disarm, such as Continuous Servo Trim or [Stats](https://github.com/iNavFlight/inav/blob/master/docs/Settings.md#stats). The new `fw_level_pitch_trim` will be saved.
115 Pre INAV 7.0, this tuning mode was called AUTO LEVEL
117 ### AUTOTUNE (FW)
118 _Tuning mode_
120 For detailed description go to https://github.com/iNavFlight/inav/wiki/Tune-INAV-PIFF-controller-for-fixedwing
122 AUTOTUNE will attempt to tune roll and pitch P, I and FF gains on a fixed-wing airplane.
124 Autotune will monitor behavior of the airplane when you fly it and adjust P, I and FF gains to reach optimal performance.
126 How to use:
128 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.
130 The more maneuvers you will do - the better results AUTOTUNE will be able to reach.
132 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.
134 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).
136 ### BEEPER
138 Make the beeper connected to the FC beep (lost model finder).
140 ### BEEPER MUTE
142 Allows the flight controller beeper to be muted by a switch. To provide some peace and quiet during setup.
144 ### BLACKBOX
146 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.
148 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.
150 See [`BLACKBOX`](/iNavFlight/inav/blob/master/docs/Blackbox.md) for more information
152 ### CAMERA CONTROL
154 Camera control 1, 2 & 3 are used to adjust settings from your RC transmitter, when analogue/HD camera's like the _Runcam Hybrid_ or _Split_ are used.
155 Available function control is -
156 1) WiFi - App connection
157 2) Power - Start/Stop record
158 3) Mode change - Alter analogue and HD image settings.
160 ### CAMSTAB
162 Allows a Pan, Tilt or Roll servo's to be used as an actively stabilized gimbal. The dedicated axis for each servo is selected in the mixer tab.
164 ### FAILSAFE
166 Lets you activate flight controller failsafe with an aux channel. This mode is primarily designed to manually test if failsafe will work when required.
167 Read [Failsafe page](https://github.com/iNavFlight/inav/wiki/Failsafe) for more info.
169 ### FLAPERON (FW)
171 Activating it moves both ailerons down (or up) by predefined offset.
173 Configuration besides activating FLAPERON mode is pretty simple, and consists of just one CLI variable:
174 - `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.
176 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).
178 ### FPV ANGLE MIX (MC)
180 This mode mixes in Pitch with a commanded ROLL stick input. Or mixes in Pitch with a commanded YAW stick input. To overcome the sweeping or arching effect that is seen via the FPV view, based on the camera's up-tilt angle. This provides a more visually appealing (true to axis) freestyle or cinematic experience.
181 Simply set `fpv_mix_degrees = X°` , to the up-tilt angle your camera is set. Then enable it together with ACRO mode. 
183 ### HEADADJ (MC)
185 It allows you to set a new yaw origin for HEADFREE mode.
187 ### HEADFREE (MC)
189 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.
191 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.
193 ### HEADING HOLD
195 This flight mode affects only yaw axis and can be enabled together with any other flight mode.
196 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.
198 Heading hold only uses yaw control (rudder) so it won't work on a flying wing which has no rudder, unless it has twin motor yaw stabilization active.
200 ### HOME RESET
202 This mode provides a means to reset the home location or arming coordinates the model will return to. This is beneficial if you choose to launch or takeoff before the model has a GPS fix.. By using this mode, you can fly past your launch site later in the flight, once a GPS fix is established.  And momentarily activate the feature.. **Ideally, it is better to place this mode on a Pot or multi-position button, so it doesn't get unintentionally bumped.**
204 ### HORIZON
206 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.
208 The biggest complaint against Horizon mode, is the abruptness in which the stock settings transition from Angle to rate. This can catch newer pilots off guard.
209 But can be made smoother by altering these setting - 
210 `max_angle_inclination_rll = 900`
211 `max_angle_inclination_pit = 900`
212 `fw_d_level = 95` OR `mc_d_level = 95`.
213 This will allow for a more linear stick feel, equivalent to Acro. And only permit the transition to occur near maximum stick deflection, or around 85° roll or pitch angle from level, when you're certain you want to command a roll or flip. This can be applied to both MC and FW platforms.
215 ### KILLSWITCH
217 Allows the flight controller to be instantly disarmed and locked out, regardless of other Settings, Saves or Checks. As with the disarm switch.
219 ### LEDLOW
221 Turns off the RGB LEDs
223 ### LOITER CHANGE (FW)
225 Reverses set loiter direction when mode selected.
227 ### MANUAL (FW)
229 Direct servo control in fixed-wing. This mode was called PASSTHROUGH mode up to version 1.8.1.
231 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.
233 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.
235 ### MC BRAKING (MC)
237 Used with POSHOLD mode, this mode provides faster manual braking when the pitch stick is released. 
238 For this mode to work, it requires `nav_user_control_mode = CRUISE` to be enabled.
239 **Use with caution**. This mode can cause temporary runaway with some settings and under some conditions.
241 ### MIXER PROFILE 2
243 This mode is primarily used to activate Mixer profile 2, which contains multirotor control and PID settings for VTOL models.
245 ### MIXER TRANSITION
247 Used to transition VTOL aircraft from the _multirotor control profile_ to the _fixedwing control profile_ and back again. This is useful for allowing a VTOL to increase forward airspeed, before entering full fixedwing flight. So as not to stall or lose altitude in the transition process. Or it can also be used to slow the aircraft in fixedwing flight, for braking and better control stability before it enters the multirotor (VTOL) state.
249 ### MSP RC OVERRIDE
251 Allows defined RC channels to be overridden by MSP `MSP_SET_RAW_RC` messages. The channels to be overridden are defined by the CLI setting `msp_override_channels`. There is a [code example](https://codeberg.org/stronnag/msp_override) that provides further information and a sample application illustrating the use of MSP RC OVERRIDE.
253 ### MULTI FUNCTION 
255 This function use a single mode to select between different functions based on feedback provided by the Multi Function OSD field. Functions are selected by briefly toggling the mode ON/OFF with this sequence, repeating until the required function is displayed in the OSD. The function is then triggered by activating the mode for > 3s. Deactivating the mode for > 3s resets everything leaving the OSD field blank. Ideally a momentary switch should be used to operate the mode although it should also work with a normal switch. Current functions include -
256 * Re-displaying any warnings
257 * Emergency landing activation
258 * Safehome suspend
259 * Trackback suspend 
260 * Turtle mode activation 
261 * Emergency arming function
263 It also provides warnings that are displayed for 10s when first triggered after which the warning disappears to be replaced with an alert symbol with a number showing the active warning total. Active warnings are then re-displayed for 5s on a rolling 30s cycle. The field is blank if there are no warnings. Current Warnings are provided for -
264 * Battery state
265 * Vibration level
266 * GPS Fix or Failure
267 * RTH Sanity (>200m heading in wrong direction)
268 * Altitude Sanity (difference between estimated and GPS altitude > 20m)
269 * Compass failure 
270 * Ground Test mode 
272 ### NAV LAUNCH (FW)
274 Airplane launch assistant
276 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.
278 Gliders have different needs than motorized planes.  See below for note on glider launch setup.
280 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.
282 `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).
284 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.
286 See INAV CLI for all available adjustable parameters, they start with `nav_fw_launch_`
288 Sequence for launching airplane using `NAV LAUNCH` mode looks like this:
290 1. Set switch to `NAV LAUNCH` mode prior to arming (note that it won't actually enable until arming)
291 1. ARM the plane. Motor should start spinning at min_throttle (if `MOTOR_STOP` is active, motor won't spin)
292 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).
293 1. Throw the airplane.  It must be thrown leveled, or thrown by slinging it by wingtip.
294 1. Motors will start at pre-configured `nav_fw_launch_thr` (default 1700) after `nav_fw_launch_motor_delay` (500ms)
295 1. Launch sequence will finish when pilot switch off the NAV LAUNCH mode or move the sticks.
297 If it won't detect launch it's possible that you need to lower your threshold. Look at the CLI variables.
299 CAUTION: Motors will spin if you unset `NAV LAUNCH` mode after arming.
301 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.
302 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.
303 If you inadvertently 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.
305 **MANUAL THROTTLE LAUNCH**
307 From INAV 6.0.0 it is possible to use NAV Launch with manual throttle control. This is really intended as a more controllable alternative to the shake to start motor and throw method of launching. When enabled using setting [nav_fw_launch_manual_throttle](https://github.com/iNavFlight/inav/blob/master/docs/Settings.md#nav_fw_launch_manual_throttle) the throttle is controlled manually throughout the launch using the throttle stick. There is no motor idle or detection used to start the motor, motor control is entirely manual and active via the throttle stick once armed. INAV only controls roll and pitch attitude during the launch climb out.
308 **NOTE:** If this option is used with no GPS fix available it is recommended to throw the plane as soon as the throttle is raised in order to avoid possible degraded control issues and premature end of the launch timeout (moving the throttle stick back to idle will reset the affected launch parameters if required).
310 **GLIDER / SLOPER SETUP**
312 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.
314 This will allow the FC to reset the launch sequence and be ready for toss with Angle activated after launch.
316 Setup launch parameters appropriately:
318 `nav_fw_launch_climb_angle = XX 45?`
320 (Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit)
322 `set nav_fw_launch_thr = 1700`
324 ^^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)
326 `nav_fw_launch_velocity = XXX 300?`
328 (Forward velocity threshold for swing-launch detection [cm/s])
330 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.
332 ### OSD ALT
334 Switches to the different alternative OSD displays ALT1, ALT2 or ALT3. The default OSD is shown when none of these are selected. 
336 ### OSD SW
338 Switches off the OSD.
340 ### PREARM
342 When PREARM is assigned a range, INAV then prevents Arming until the PREARM condition is met and will raise a prearm error if Arming is attempted. After the craft is armed, then INAV stops monitoring the PREARM condition.
344 ### SERVO AUTOTRIM (FW)
345 _Tuning mode_
347 In flight adjustment of servo midpoint for straight flight
349 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.
351 _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._
353 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.
355 How to use:
357 1. This is intended to use in air.
358 2. Fly straight, choose what mode that suites you best. (`manual`, `angle` or `acro`)
359 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.
360 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.
362 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.
364 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 ).
366 ### SOARING (FW)
368 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.
370 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`.
372 ### SURFACE
374 Enable terrain following when you have a rangefinder enabled
376 ### TELEMETRY
378 ### TURN ASSIST
380 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.
382 In RATE mode pilot compensated for this effect by using both ROLL and YAW sticks to coordinate the rotation and keep attitude (horizon line).
384 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.
386 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.
388 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.
390 From INAV 1.7 turn assist will work one planes, copy paste from pull request:
392 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.
394 TAS (from airspeed sensor) will be used for calculation if available - otherwise code will use cruise airspeed defined by fw_reference_airspeed.
396 ### TURTLE (MC)
398 Provides a means of flipping over a multicopter that has crash landed upside down, by using the roll or pitch sticks.
400 ### USER 
401 These are shown as USER1 & USER2 & USER3 & USER4 and also known as `PinIO` , when broken out on many flight controllers.
402 The four USER selections are generic in nature. But are often used for certain functions, depending on what the flight controller manufacturer decides to place on that mode.
404 **e.g.**
405 - Some FC manufactures have `USER 1` as a VTX power switch. Which includes the electronic hardware, to power ON and OFF your HD or Analogue VTX.
406 - They may also add the flight controller hardware to allow for analogue dual camera switching on `USER 2`.
407 - While it is common to see `USER 3` selected to turn ON or OFF the power to a free standing HD camera. 
408 - And `USER 4` to allow for the remote Start/Stop recording of a free standing HD camera.
410 **Note:** This should not be taken as a set order. Always read the hardware definition in FC manufacturers manual. 
412 ### WP Planner
414 This is a Navigation-Mode that allows you to plot a waypoint mission as you fly. See more [details](https://github.com/iNavFlight/inav/wiki/Navigation-modes#wp-planner---on-the-fly-waypoint-mission-planner)
416 # AUXILIARY CONFIGURATION
418 Spare auxiliary receiver channels can be used to enable/disable modes.  Some modes can only be enabled this way.
420 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).
422 _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._
424 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.
426 When a channel is within a specified range the corresponding mode is enabled.
428 Use the GUI configuration tool to allow easy configuration when channel.
430 ### CLI
432 There is a CLI command, `aux` that allows auxiliary configuration.  It takes 5 arguments as follows:
434 * AUD range slot number (0 - 39)
435 * mode id (see mode list below)
436 * AUX channel index (AUX1 = 0, AUX2 = 1,... etc)
437 * low position, from 900 to 2100. Should be a multiple of 25.
438 * high position, from 900 to 2100. Should be a multiple of 25.
440 If the low and high position are the same then the values are ignored.
442 e.g.
444 Configure AUX range slot 0 to enable ARM when AUX1 is within 1700 and 2100.
447 aux 0 0 0 1700 2100
450 You can display the AUX configuration by using the `aux` command with no arguments.
452 ### Mode ID List
453 *  "ARM"        0
454 *  "ANGLE"      1
455 *  "HORIZON"    2
456 *  "NAV ALTHOLD"        3
457 *  "HEADING HOLD"       5
458 *  "HEADFREE"   6
459 *  "HEADADJ"    7
460 *  "CAMSTAB"    8
461 *  "NAV RTH"    10
462 *  "NAV POSHOLD"        11
463 *  "MANUAL"     12
464 *  "BEEPER"     13
465 *  "LEDS OFF"   15
466 *  "LIGHTS"     16
467 *  "OSD OFF"    19
468 *  "TELEMETRY"  20
469 *  "AUTO TUNE"  21
470 *  "BLACKBOX"   26
471 *  "FAILSAFE"   27
472 *  "NAV WP"     28
473 *  "AIR MODE"   29
474 *  "HOME RESET" 30
475 *  "GCS NAV"    31
476 *  "FPV ANGLE MIX"      32
477 *  "SURFACE"    33
478 *  "FLAPERON"   34
479 *  "TURN ASSIST"        35
480 *  "NAV LAUNCH" 36
481 *  "SERVO AUTOTRIM"     37
482 *  "KILLSWITCH" 38
483 *  "CAMERA CONTROL 1"   39
484 *  "CAMERA CONTROL 2"   40
485 *  "CAMERA CONTROL 3"   41
486 *  "OSD ALT 1"  42
487 *  "OSD ALT 2"  43
488 *  "OSD ALT 3"  44
489 *  "NAV COURSE HOLD"    45
490 *  "MC BRAKING" 46
491 *  "USER1"      47
492 *  "USER2"      48
493 *  "LOITER CHANGE"      49
494 *  "MSP RC OVERRIDE"    50
495 *  "PREARM"     51
496 *  "TURTLE"     52
497 *  "NAV CRUISE" 53
498 *  "AUTO LEVEL" 54
499 *  "WP PLANNER" 55
500 *  "SOARING"    56