Add new OSD document
[inav.git] / docs / Navigation.md
blob6caf4dc628fedc4ff176bc0f6ea5c09dd98c6d26
1 # Navigation
3 The 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, GPS or rangefinder. The best source is chosen automatically. 
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 By default, GPS is available as an altitude source for airplanes only. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled.
12 ### CLI parameters affecting ALTHOLD mode:
13 * *nav_use_midthr_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.
14 * *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF. 
16 ### Related PIDs
17 PIDs affecting altitude hold: ALT & VEL
18 PID meaning:
19 * ALT - translates altitude error to desired climb rate and acceleration. Tune P for altitude-to-velocity regulator and I for velocity-to-acceleration regulator
20 * VEL - translated Z-acceleration error to throttle adjustment
22 ## Throttle tilt compensation
24 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 *throttle_tilt_comp_str* CLI variable.
26 ## NAV POSHOLD mode - position hold
28 Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
29 When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
31 ### CLI parameters affecting POSHOLD mode:
32 * *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.
33 * *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF. 
35 ### Related PIDs
36 PIDs affecting position hold: POS, POSR
37 PID meaning:
38 * POS - translated position error to desired velocity, uses P term only
39 * POSR - translates velocity error to desired acceleration
41 ## NAV RTH - return to home mode
43 Home for RTH is the position where vehicle was first armed. This position may be offset by the CLI settings `nav_rth_home_offset_distance` and `nav_rth_home_offset_direction`. This position may also be overridden with Safehomes. RTH requires accelerometer, compass and GPS sensors.
45 RTH requires barometer for multirotor, unless unless *inav_use_gps_no_baro* is enabled.
47 RTH will maintain altitude during the return. When home is reached, a copter will attempt automated landing. An airplane will either loiter around the home position, or attempt an automated landing, depending on your settings.
48 When deciding what altitude to maintain, RTH has 6 different modes of operation (controlled by *nav_rth_alt_mode* and *nav_rth_altitude* cli variables):
49 * 0 (NAV_RTH_NO_ALT) - keep current altitude during whole RTH sequence (*nav_rth_altitude* is ignored)
50 * 1 (NAV_RTH_EXTRA_ALT) - climb to current altitude plus extra margin prior to heading home (*nav_rth_altitude* defines the extra altitude (cm))
51 * 2 (NAV_RTH_CONST_ALT) - climb/descend to predefined altitude before heading home (*nav_rth_altitude* defined altitude above launch point (cm))
52 * 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)
53 * 4 (NAV_RTH_AT_LEAST_ALT) - same as 2 (NAV_RTH_CONST_ALT), but only climb, do not descend
54 * 5 (NAV_RTH_AT_LEAST_ALT_LINEAR_DESCENT) - Same as 4 (NAV_RTH_AT_LEAST_ALT). But, if above the RTH Altitude, the aircraft will gradually descend to the RTH Altitude. The target is to reach the RTH Altitude as it arrives at the home point. This is to save energy during the RTH.
56 ## NAV WP - Waypoint mode
58 NAV WP allows the craft to autonomously navigate a set route defined by waypoints that are loaded into the FC as a predefined mission.
60 ## CLI command `wp` to manage waypoints
62 `wp` - List all waypoints.
64 `wp load` - Load list of waypoints from EEPROM to FC.
66 `wp <n> <action> <lat> <lon> <alt> <p1> <p2> <p3> <flag>` - Set parameters of waypoint with index `<n>`. Note that prior to INAV 2.5, the `p2` and `p3` parameters were not required. From 2.5, INAV will accept either version but always saves and lists the later full version.
68 Parameters:
70   * `<action>` - The action to be taken at the WP. The following are enumerations are available in INAV 2.6 and later:
71       *  0 - Unused / Unassigned
72       *  1 - WAYPOINT
73       *  3 - POSHOLD_TIME
74       *  4 - RTH
75           *  5 - SET_POI
76       *  6 - JUMP
77       *  7 - SET_HEAD
78       *  8 - LAND
80   * `<lat>` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789).
82   * `<lon>` - Longitude.
84   * `<alt>` - Altitude in cm. See `p3` bit 0 for datum definition.
86   * `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI.
88   * `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
90   * `<p3>` - A  bitfield with four bits reserved for user specified actions. It is anticipated that these actions will be exposed through the logic conditions.
91       * Bit 0 - Altitude (`alt`) : Relative (to home altitude) (0) or Absolute (AMSL) (1).
92           * Bit 1 - WP Action 1
93           * Bit 2 - WP Action 2
94       * Bit 3 - WP Action 3
95       * Bit 4 - WP Action 4
96           * Bits 5 - 15 : undefined / reserved.
98       Note:
100           * If `p2` is specified, then `p3` is also required.
101           * `p3` is only defined for navigable WP types (WAYPOINT, POSHOLD_TIME, LAND). The affect of specifying a non-zero `p3` for other WP types is undefined.
103   * `<flag>` - Last waypoint must have `flag` set to 165 (0xA5).
105 `wp save` - Checks list of waypoints and save from FC to EEPROM (warning: it also saves all unsaved CLI settings like normal `save`).
107 `wp reset` - Resets the list, sets the number of waypoints to 0 and marks the list as invalid (but doesn't delete the waypoint definitions).
109 ### `wp` example
112 # wp load
114 # wp
115 # wp 11 valid
116 wp 0 1 543533193 -45179273 3500 0 0 0 0
117 wp 1 1 543535723 -45193913 3500 0 0 0 0
118 wp 2 1 543544541 -45196617 5000 0 0 0 0
119 wp 3 1 543546578 -45186895 5000 0 0 0 0
120 wp 4 6 0 0 0 1 2 0 0
121 wp 5 1 543546688 -45176009 3500 0 0 0 0
122 wp 6 1 543541225 -45172673 3500 0 0 0 0
123 wp 7 6 0 0 0 0 1 0 0
124 wp 8 3 543531383 -45190405 3500 45 0 0 0
125 wp 9 1 543548470 -45182104 3500 0 0 0 0
126 wp 10 8 543540521 -45178091 6000 0 0 0 165
127 wp 11 0 0 0 0 0 0 0 0
129 wp 59 0 0 0 0 0 0 0 0
132 Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.
134 ## Multi-missions
136 Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command.
138 E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0).
140 wp 0 1 545722109 -32869291 5000 0 0 0 0
141 wp 1 1 545708178 -32642698 5000 0 0 0 0
142 wp 2 1 545698227 -32385206 5000 0 0 0 165
144 wp 0 1 545599696 -32958555 5000 0 0 0 0
145 wp 1 1 545537978 -32958555 5000 0 0 0 0
146 wp 2 1 545547933 -32864141 5000 0 0 0 0
147 wp 3 1 545597705 -32695913 5000 0 0 0 0
148 wp 4 1 545552910 -32598066 5000 0 0 0 0
149 wp 5 6 0 0 0 0 0 0 165
151 wp 0 1 545714148 -32501936 5000 0 0 0 165
153 # wp save
156 Multi Mission after saving:
158 # wp
159 # wp 10 valid
160 wp 0 1 545722109 -32869291 5000 0 0 0 0
161 wp 1 1 545708178 -32642698 5000 0 0 0 0
162 wp 2 1 545698227 -32385206 5000 0 0 0 165
163 wp 3 1 545599696 -32958555 5000 0 0 0 0
164 wp 4 1 545537978 -32958555 5000 0 0 0 0
165 wp 5 1 545547933 -32864141 5000 0 0 0 0
166 wp 6 1 545597705 -32695913 5000 0 0 0 0
167 wp 7 1 545552910 -32598066 5000 0 0 0 0
168 wp 8 6 0 0 0 0 0 0 165
169 wp 9 1 545714148 -32501936 5000 0 0 0 165
170 wp 10 0 0 0 0 0 0 0 0
171 wp 11 0 0 0 0 0 0 0 0
172 wp 12 0 0 0 0 0 0 0 0
174 wp 59 0 0 0 0 0 0 0 0
176 ### Changing Mission-Index in flight
177 The MISSION CHANGE mode allows to switch between multiple stored missions in flight. With mode active the required mission index can be selected by cycling through missions using the WP mode switch. Selected mission is loaded when mission change mode is switched off. Mission index can also be changed through addition of a new Mission Index adjustment function which should be useful for DJI users unable to use the normal OSD mission related fields.