1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

Merge branch 'master' of https://github.com/RomanLut/inav into submit-gps-fix-estimation

This commit is contained in:
Roman Lut 2023-08-04 00:57:19 +02:00
commit 2b9a5a6a8d
178 changed files with 5846 additions and 2036 deletions

View file

@ -62,12 +62,14 @@ beeper list
giving:
```
Available: RUNTIME_CALIBRATION HW_FAILURE RX_LOST RX_LOST_LANDING DISARMING ARMING ARMING_GPS_FIX BAT_CRIT_LOW BAT_LOW GPS_STATUS RX_SET ACTION_SUCCESS ACTION_FAIL READY_BEEP MULTI_BEEPS DISARM_REPEAT ARMED SYSTEM_INIT ON_USB LAUNCH_MODE CAM_CONNECTION_OPEN CAM_CONNECTION_CLOSED ALL PREFERED
Available: RUNTIME_CALIBRATION HW_FAILURE RX_LOST RX_LOST_LANDING DISARMING ARMING ARMING_GPS_FIX BAT_CRIT_LOW
BAT_LOW GPS_STATUS RX_SET ACTION_SUCCESS ACTION_FAIL READY_BEEP MULTI_BEEPS DISARM_REPEAT ARMED SYSTEM_INIT
ON_USB LAUNCH_MODE CAM_CONNECTION_OPEN CAM_CONNECTION_CLOSED ALL PREFERED
```
The `beeper` command syntax follows that of the `feature` command; a minus (`-`) in front of a name disables that function.
So to disable the beeper / buzzer when connected to USB (may enhance domestic harmony)
So to disable the beeper / buzzer when powered by USB (may enhance domestic harmony):
```
beeper -ON_USB
@ -78,17 +80,39 @@ Now the `beeper` command will show:
```
# beeper
Disabled: ON_USB
```
*Note: SYSTEM_INIT sequence is not affected by ON_USB setting and will still be played on USB connection. Disable both ON_USB and SYSTEM_INIT to disable buzzer completely when FC is powered from USB.*
*Note: ON_USB setting requires present and configured battery voltage metter.*
To disable all features use:
```
beeper -ALL
```
To store current set to preferences use (preferences also require ```save```):
```
beeper PREFERED
```
To restore set from preferences use:
```
beeper -PREFERED
As with other CLI commands, the `save` command is needed to save the new settings.
## Types of buzzer supported
The buzzers are enabled/disabled by simply enabling or disabling a GPIO output pin on the board.
Most FCs require ACTIVE buzzers. Active buzzers are enabled/disabled by simply enabling or disabling a GPIO output pin on the board.
This means the buzzer must be able to generate its own tone simply by having power applied to it.
Buzzers that need an analog or PWM signal do not work and will make clicking noises or no sound at all.
Passive buzzers that need an analog or PWM signal do not work and will make clicking noises or no sound at all.
Passive buzzers are supported on FCs which are designed to work with passive buzzers only (so far there is no available, except rare cases like Matek F765-WSE where passive buzzer is preinstalled).
Examples of a known-working buzzers.

View file

@ -44,6 +44,10 @@ The stick positions are combined to activate different functions:
| Bypass Nav Arm disable | LOW | HIGH | CENTER | CENTER |
| Save setting | LOW | LOW | LOW | HIGH |
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
| Enter Camera OSD(RuncamDevice)| RIGHT | CENTER | CENTER | CENTER |
| Exit Camera OSD (RuncamDevice)| LEFT | CENTER | CENTER | CENTER |
| Confirm - Camera OSD | RIGHT | CENTER | CENTER | CENTER |
| Navigation - Camera OSD | CENTER | CENTER | * | * |
For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/).
![Stick Positions](assets/images/StickPositions.png)

View file

@ -4,11 +4,14 @@ The navigation system in INAV is responsible for assisting the pilot allowing al
## NAV ALTHOLD mode - altitude hold
Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically. GPS is available as an altitude source for airplanes only.
Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically.
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.
By default, GPS is available as an altitude source for airplanes only. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled.
### CLI parameters affecting ALTHOLD mode:
* *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.
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.
### Related PIDs
PIDs affecting altitude hold: ALT & VEL
@ -22,12 +25,13 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co
## NAV POSHOLD mode - position hold
Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
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.
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.
### CLI parameters affecting POSHOLD mode:
* *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.
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.
### Related PIDs
PIDs affecting position hold: POS, POSR
PID meaning:
@ -38,9 +42,9 @@ PID meaning:
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.
If barometer is NOT present, RTH will fly directly to home, altitude control here is up to pilot.
RTH requires barometer for multirotor, unless unless *inav_use_gps_no_baro* is enabled.
If barometer is present, 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.
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.
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):
* 0 (NAV_RTH_NO_ALT) - keep current altitude during whole RTH sequence (*nav_rth_altitude* is ignored)
* 1 (NAV_RTH_EXTRA_ALT) - climb to current altitude plus extra margin prior to heading home (*nav_rth_altitude* defines the extra altitude (cm))

167
docs/OSD.md Normal file
View file

@ -0,0 +1,167 @@
# On Screen Display
The On Screen Display, or OSD, is a feature that overlays flight data over the video image. This can be done on the flight controller, using the analogue MAX7456 chip. Digital systems take the OSD data, via MSP DisplayPort, send it to the video receiver; which combines the data with the image. You can specify what elements are displayed, and their locations on the image. Most systems are character based, and use the MAX7456 analogue setup, or MSP DisplayPort. However, there are some different systems which are also supported. Such as the canvas based FrSKY PixelOSD on analogue. Canvas OSDs draw shapes on the image. Whereas character based OSDs use font characters to display the data.
## Features and Limitations
Not all OSDs are created equally. This table shows the differences between the different systems available.
| OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported |
|---------------|-------------------|-----------|-----------|-------------------|---------------------------|
| Analogue PAL | 30 x 16 | X | | | YES |
| Analogue NTSC | 30 x 13 | X | | | YES |
| PixelOSD | As PAL or NTSC | | X | | YES |
| DJI OSD | 30 x 16 | X | | | NO - BF Characters only |
| DJI WTFOS | 60 x 22 | X | | X | YES |
| HDZero | 50 x 18 | X | | X | YES |
| Avatar | 53 x 20 | X | | X | YES |
| DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only |
## OSD Elements
Here are the OSD Elements provided by INAV.
| ID | Element | Added |
|-------|-----------------------------------------------|-------|
| 0 | OSD_RSSI_VALUE | 1.0.0 |
| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 |
| 2 | OSD_CROSSHAIRS | 1.0.0 |
| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 |
| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 |
| 5 | OSD_ONTIME | 1.0.0 |
| 6 | OSD_FLYTIME | 1.0.0 |
| 7 | OSD_FLYMODE | 1.0.0 |
| 8 | OSD_CRAFT_NAME | 1.0.0 |
| 9 | OSD_THROTTLE_POS | 1.0.0 |
| 10 | OSD_VTX_CHANNEL | 1.0.0 |
| 11 | OSD_CURRENT_DRAW | 1.0.0 |
| 12 | OSD_MAH_DRAWN | 1.0.0 |
| 13 | OSD_GPS_SPEED | 1.0.0 |
| 14 | OSD_GPS_SATS | 1.0.0 |
| 15 | OSD_ALTITUDE | 1.0.0 |
| 16 | OSD_ROLL_PIDS | 1.6.0 |
| 17 | OSD_PITCH_PIDS | 1.6.0 |
| 18 | OSD_YAW_PIDS | 1.6.0 |
| 19 | OSD_POWER | 1.6.0 |
| 20 | OSD_GPS_LON | 1.6.0 |
| 21 | OSD_GPS_LAT | 1.6.0 |
| 22 | OSD_HOME_DIR | 1.6.0 |
| 23 | OSD_HOME_DIST | 1.6.0 |
| 24 | OSD_HEADING | 1.6.0 |
| 25 | OSD_VARIO | 1.6.0 |
| 26 | OSD_VARIO_NUM | 1.6.0 |
| 27 | OSD_AIR_SPEED | 1.7.3 |
| 28 | OSD_ONTIME_FLYTIME | 1.8.0 |
| 29 | OSD_RTC_TIME | 1.8.0 |
| 30 | OSD_MESSAGES | 1.8.0 |
| 31 | OSD_GPS_HDOP | 1.8.0 |
| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 |
| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 |
| 34 | OSD_HEADING_GRAPH | 1.8.0 |
| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 |
| 36 | OSD_WH_DRAWN | 1.9.0 |
| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 |
| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 |
| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 |
| 40 | OSD_TRIP_DIST | 1.9.1 |
| 41 | OSD_ATTITUDE_PITCH | 2.0.0 |
| 42 | OSD_ATTITUDE_ROLL | 2.0.0 |
| 43 | OSD_MAP_NORTH | 2.0.0 |
| 44 | OSD_MAP_TAKEOFF | 2.0.0 |
| 45 | OSD_RADAR | 2.0.0 |
| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 |
| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 |
| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 |
| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 |
| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 |
| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 |
| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 |
| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 |
| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 |
| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 |
| 56 | OSD_LEVEL_PIDS | 2.0.0 |
| 57 | OSD_POS_XY_PIDS | 2.0.0 |
| 58 | OSD_POS_Z_PIDS | 2.0.0 |
| 59 | OSD_VEL_XY_PIDS | 2.0.0 |
| 60 | OSD_VEL_Z_PIDS | 2.0.0 |
| 61 | OSD_HEADING_P | 2.0.0 |
| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 |
| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 |
| 64 | OSD_RC_EXPO | 2.0.0 |
| 65 | OSD_RC_YAW_EXPO | 2.0.0 |
| 66 | OSD_THROTTLE_EXPO | 2.0.0 |
| 67 | OSD_PITCH_RATE | 2.0.0 |
| 68 | OSD_ROLL_RATE | 2.0.0 |
| 69 | OSD_YAW_RATE | 2.0.0 |
| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 |
| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 |
| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 |
| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 |
| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 |
| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 |
| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 |
| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 |
| 78 | OSD_DEBUG | 2.0.0 |
| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 |
| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 |
| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 |
| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 |
| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 |
| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 |
| 85 | OSD_3D_SPEED | 2.1.0 |
| 86 | OSD_IMU_TEMPERATURE | 2.1.0 |
| 87 | OSD_BARO_TEMPERATURE | 2.1.0 |
| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 |
| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 |
| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 |
| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 |
| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 |
| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 |
| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 |
| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 |
| 96 | OSD_ALTITUDE_MSL | 2.1.0 |
| 97 | OSD_PLUS_CODE | 2.1.0 |
| 98 | OSD_MAP_SCALE | 2.2.0 |
| 99 | OSD_MAP_REFERENCE | 2.2.0 |
| 100 | OSD_GFORCE | 2.2.0 |
| 101 | OSD_GFORCE_X | 2.2.0 |
| 102 | OSD_GFORCE_Y | 2.2.0 |
| 103 | OSD_GFORCE_Z | 2.2.0 |
| 104 | OSD_RC_SOURCE | 2.2.0 |
| 105 | OSD_VTX_POWER | 2.2.0 |
| 106 | OSD_ESC_RPM | 2.3.0 |
| 107 | OSD_ESC_TEMPERATURE | 2.5.0 |
| 108 | OSD_AZIMUTH | 2.6.0 |
| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 |
| 110 | OSD_CRSF_LQ | 2.6.0 |
| 111 | OSD_CRSF_SNR_DB | 2.6.0 |
| 112 | OSD_CRSF_TX_POWER | 2.6.0 |
| 113 | OSD_GVAR_0 | 2.6.0 |
| 114 | OSD_GVAR_1 | 2.6.0 |
| 115 | OSD_GVAR_2 | 2.6.0 |
| 116 | OSD_GVAR_3 | 2.6.0 |
| 117 | OSD_TPA | 2.6.0 |
| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 |
| 119 | OSD_VERSION | 3.0.0 |
| 120 | OSD_RANGEFINDER | 3.0.0 |
| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 |
| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 |
| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 |
| 124 | OSD_GLIDESLOPE | 3.0.1 |
| 125 | OSD_GPS_MAX_SPEED | 4.0.0 |
| 126 | OSD_3D_MAX_SPEED | 4.0.0 |
| 127 | OSD_AIR_MAX_SPEED | 4.0.0 |
| 128 | OSD_ACTIVE_PROFILE | 4.0.0 |
| 129 | OSD_MISSION | 4.0.0 |
| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 |
| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 |
| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 |
| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 |
| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 |
| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 |
| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 |
| 137 | OSD_GLIDE_RANGE | 6.0.0 |
| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 |
| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 |
| 140 | OSD_GROUND_COURSE | 6.0.0 |
| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 |
| 142 | OSD_PILOT_NAME | 6.0.0 |
| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 |

View file

@ -1432,6 +1432,26 @@ Which SBAS mode to be used
---
### gps_ublox_nav_hz
Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer.
| Default | Min | Max |
| --- | --- | --- |
| 10 | 5 | 200 |
---
### gps_ublox_use_beidou
Enable use of Beidou satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps hardware support [OFF/ON].
| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |
---
### gps_ublox_use_galileo
Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON].
@ -1442,6 +1462,16 @@ Enable use of Galileo satellites. This is at the expense of other regional const
---
### gps_ublox_use_glonass
Enable use of Glonass satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps haardware support [OFF/ON].
| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |
---
### ground_test_mode
For developer ground test use. Disables motors, sets heading status = Trusted on FW.
@ -3202,6 +3232,16 @@ Defines at what altitude the descent velocity should start to be `nav_land_minal
---
### nav_landing_bump_detection
Allows immediate landing detection based on G bump at touchdown when set to ON. Requires a barometer and currently only works for multirotors.
| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |
---
### nav_manual_climb_rate
Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]

Binary file not shown.

Before

Width:  |  Height:  |  Size: 718 KiB

After

Width:  |  Height:  |  Size: 774 KiB

Before After
Before After

File diff suppressed because it is too large Load diff

Before

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 819 KiB

View file

@ -0,0 +1,53 @@
# Introduction
While many of the instructions here are somewhat generic and will likely work for other projects, the goal of these instructions is to assist a non-developer INAV user to acquire firmware that includes a pull request so he can flash it on his supported fc.
Building the pull request manually or using custom/unofficial targets is not the focus of this document.
# Why should you test a pull request?
- You want to volunteer time and resources helping improving INAV for everyone by catching issues before they are introduced in the next release of INAV!
- You reported or are affected by a bug that has been addressed by this pull request and want to help test the fix
- You are interested in testing a new feature implemented by this pull request
# Why should you not test a pull request?
- Pull requests are beta code and may have bugs; bugs may cause you to crash and damage your model
- Upgrading from the stable version of INAV may require changes to your config that are not yet fully documented
# Before you proceed
- Read the comments on the pull request you want to test. It may provide useful context and information on known issues, required configuration changes or what branch of the inav-configurator is required.
- Make sure the pull request has passed all checks, otherwise you may not have pre-compiled firmware images.
- Make a diff all backup of your existing INAV configuration.
- Take notes of what INAV target you are using.
- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](http://seyrsnys.myzen.co.uk/inav-configurator-next/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI.
# Finding the pull request
This is easy, but you will need to be logged in to your GitHub account.
Navigate to the INAV github project and click on [``Pull Requests``](https://github.com/iNavFlight/inav/pulls).
You can just scroll through the list to find a pull request you are interested in, or use the filter bar by typing the name of the pull request, or the number, if you know it.
![Search results](assets/pr_testing/pr_search_result.png)
Once you find the one you are looking for, go ahead an open it!
Click on the ``Checks`` tab
Click on ``Build firmware``, it should take you to the ``Actions`` tab.
![Search results](assets/pr_testing/build_firmware.png)
You should see a summary with a column saying ``Artifacts`` and a number. Click on the number to be taken to the list of artifacts.
![Search results](assets/pr_testing/actions_summary.png)
On the ``Artifacts`` list, there should be an artifact without SITL in its name.
![Search results](assets/pr_testing/artifact_listing.png)
Click on it to download the zip file containing pre-compiled firmware images for all INAV official targets. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings.
# I have flashed the new firmware, what should I do next?
- You should configure your model, either manually from scratch, or by loading your diff file. Keep in mind that loading a diff file may not always work, as there may have been some other changes in INAV that require attention. But even if you start from scratch, there are usually many sections that are safe to copy over from your diff.
- Try to reproduce the bug reported or play around with the new feature.
- Once you are done testing, don't forget to report your results on the pull request. Both positive results and issues are valid and welcome feedback.

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 71 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 26 KiB