Change MAVLink function mask back to 256 (#489)
[betaflight.git] / docs / Navigation.md
blob9d33f10645ba71a26b56dbcd725de147bba796b5
1 # Navigation
3 Navigation system in INAV is responsible for assisting the pilot allowing altitude and position hold, return-to-home and waypoint flight.
5 ## NAV ALTHOLD mode - altitude hold
7 Altitude hold requires a valid source of altitude - barometer or sonar. The best source is chosen automatically. GPS is available as an altitude source for airplanes only.
8 In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - quad goes up, pilot moves stick down - quad descends, you keep stick at neutral position - quad hovers.
10 ### CLI parameters affecting ALTHOLD mode:
11 * *nav_use_midrc_for_althold* - when set to "0", firmware will remember where your throttle stick was when ALTHOLD was activated - this will be considered neutral position. When set to "1" - 50% throttle will be considered neutral position.
12 * *nav_throttle_tilt_comp* - when set to "1" firmware will automatically increase throttle when copter is tilted and in ALTHOLD mode.
14 ### Related PIDs
15 PIDs affecting altitude hold: ALT & VEL
16 PID meaning:
17 * ALT - translates altitude error to desired climb rate and acceleration. Tune P for altitude-to-velocity regulator and I for velocity-to-acceleration regulator
18 * VEL - translated Z-acceleration error to throttle adjustment
20 ## Throttle tilt compensation
22 Throttle tilt compensation attempts to maintain constant vertical thrust when copter is tilted giving additional throttle if tilt angle (pitch/roll) is not zero. Controlled by *nav_throttle_tilt_comp* CLI variable.
24 ## NAV POSHOLD mode - position hold
26 Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
27 When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). Can be activated together with ALTHOLD to get a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
29 ### CLI parameters affecting ALTHOLD mode:
30 * *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
32 ### Related PIDs
33 PIDs affecting position hold: POS, POSR
34 PID meaning:
35 * POS - translated position error to desired velocity, uses P term only
36 * POSR - translates velocity error to desired acceleration
38 ## NAV RTH - return to home mode
40 Home for RTH is position, where copter was armed. RTH requires accelerometer, compass and GPS sensors.
42 If barometer is NOT present, RTH will fly directly to home, altitude control here is up to pilot.
44 If barometer is present, RTH will maintain altitude during the return and when home is reached copter will attempt automated landing.
45 When deciding what altitude to maintain, RTH has 4 different modes of operation (controlled by *nav_rth_alt_mode* and *nav_rth_altitude* cli variables):
46 * 0 (NAV_RTH_NO_ALT) - keep current altitude during whole RTH sequence (*nav_rth_altitude* is ignored)
47 * 1 (NAX_RTH_EXTRA_ALT) - climb to current altitude plus extra margin prior to heading home (*nav_rth_altitude* defines the extra altitude (cm))
48 * 2 (NAV_RTH_CONST_ALT) - climb/descend to predefined altitude before heading home (*nav_rth_altitude* defined altitude above launch point (cm))
49 * 3 (NAV_RTH_MAX_ALT) - track maximum altitude of the whole flight, climb to that altitude prior to the return (*nav_rth_altitude* is ignored)
50 * 4 (NAV_RTH_AT_LEAST_ALT) - same as 2 (NAV_RTH_CONST_ALT), but only climb, do not descend