Skip to main content

INAV 8.0.1 - Gallant Goshawk

INAV 8.0.1 Gallant Goshawk

Please carefully read the release notes for the best possible experience and safety.

Contact other pilots, share experiences, suggestions and ask for help on:

[put social cards here]

info

INAV 8 no longer includes F411 targets as part of the official release.

note

GPS: UBLOX7 and UBLOX have been merged into a single UBLOX option, and units with older firmware are now deprecated. Only M8 and newer will be supported in the future.

warning

Make sure to remove props and check your motor and servo outputs before powering your upgraded flight controller with a battery for the first time. The changes to enable flexible motor and servo allocation may change what outputs your configuration uses by default.

Known Issues in 8.0​

  • see github

Upgrading from a previous release​

Upgrading from INAV 7.0 and 7.1​

  1. Backup configuration with CLI diff all command
  2. Download and install the new INAV Configurator 8.0
  3. Flash INAV 8.0 WITH Full Chip Erase option enabled
  4. Edit the 7.x diff and apply Diff breaking changes described below, and save it as your new inav 8 diff. See Diff breaking changes section below.
  5. Select Keep current settings from the defaults pop-up
  6. Go to CLI and restore your edited inav diff
  7. Done

Upgrading from older versions​

Highlights​

Geozones​

The Geozone feature allows pilots to define one or multiple areas on the map in Mission Control, to prevent accidental flying outside of allowed zones (Flight-Zones, FZ) or to avoid certain areas they are not allowed or not willing to fly in (No-Flight-Zone, NFZ). This type of feature might be known to many pilots as a "Geofence" and despite providing the same core functionality, INAV Geozones are significantly more versatile and provide more safety and features. Read the Documentation for more info IMPORTANT: Geozones will not be available for STM32F722 based Flight Controllers due to insufficient flash storage.

GPS Fix estimation (dead reckoning, RTH without GPS fix) for Airplanes​

This new feature allows INAV to return to its launch location, in case of a failed GPS due to hardware failure or interference. INAV will use the remaining sensors and the already calculated wind speed and direction, to blindly return towards the home location. For this feature, no extra sensors are strictly necessary, aside from the standard Accelerometer, Gyroscope and Barometer, but its highly recommended to have a compass and for best precision, to also have an Airspeed sensor. The feature will not be able to precisely return to the pilot, but it allows the Aircraft to either get out of an area with interferences, or to give the pilot time and a chance to regain control for a manual return, when the aircraft is closer. Details here

MSP-Linkstats​

A new MSP Message that allows RC links that communicate with the Flight controller via MSP, to provide Link Information to INAV like LQ, RSSI, Power Level, SNR and more. The first RC Link to support this is the mLRS Project with more possibly coming in the future. Details here

MSP-VTX​

MSP-VTX has been updated by @geoffsim to increase compatibility with HDZero vtxs.

The previously simple Mavlink Telemetry was extended to be compatible with flow control capable links (Thanks @MUSTARDTIGERFPV). This now allows RC Control via Mavlink and Telemetry at the same time over a Single UART. It is tested successfully with ELRS Mavlink-RC and mLRS Mavlink. Additionally it allows the Use of Mission Planner, QGroundControl and potentially other GCS Applications to be used for Flight Monitoring with INAV. Note: To receive RSSI and LQ for ELRS Mavlink-RC you need to set mavlink_radio_type=ELRS in the CLI. Details here

Walksnail Serial Gimbal and Headtracker support​

INAV now also supports the Caddx / Walksnail GM Series Gimbals. These can now be controlled via a dedicated uart UART or via MSP and don't need up to 3 PWM Outputs anymore. This enables the direct Gimbal Control via Head Tracking from Walksnail goggles, without additional wiring. Details Here

OSD Updates​

ADSB Receiver Support​

It is now possible to connect an ADSB receiver to your flight controller and get OSD Warnings if any ADSB enabled Aircraft, is close by. INAV Configurator can show these Aircraft on the map for additional safety of UAV flights. ADSB is supported for generally available receivers like uAvionix pingRX (not tested) and Aerobit TT-SC1 (tested) and should also work with the upcoming PicoADSB Details here

I-Term Lock for Fixed Wing​

The Fixed Wing PIDFF Controller was reworked. The PIDs are now attenuated based in the amount of Setpoint (Stick deflection in Acro Mode) for a more "Manual" flight feel during aggressive inputs while keeping the locked in feel of a PID-Assisted flight. This allows the Pilot to have a PID tune with very high P and I values for a locked in flight feel, while keeping a good manual feeling of the plane's flight characteristics, especially when flying slow. Additionally the Attenuation fixes the Bounce-Back caused by the Integral of the PID controller, after sharp roll or pitch inputs. Details Here

U-Blox AssistNow Support in INAV Configurator​

AssistNow is a Service that provides GPS Satellite information data for offline-applications, to dramatically increase the time to fix for GPS Devices. By Providing your own AssistNow Token, INAV Configurator can automatically download the latest data set and transfer it to any connected INAV UAV. With this, a GPS fix after cold start should merely take seconds instead of minutes. This is especially helpful for people who go fly with a big fleet of aircraft. Details here

Sensor ID change for SmartPort telemetry​

The sensor IDs for the Modes and GNSS data have changed in SmartPort telemetry. The default settings in INAV are to now use the new sensor IDs. The INAV OpenTX-Telemetry-Widget has been updated to use these new IDs. So you will not see any issues when using the latest version of this widget. However, if you use another widget or app that uses the SmartPort telemetry. It is recommended to inform the creator of the app/widget, as the old sensor IDs will be removed in INAV 10.0.0. Details here

You can change INAV to use the old sensor IDs with the CLI parameter set frsky_use_legacy_gps_mode_sensor_ids = on. However, it is recommended to only use this only as long as necessary. This parameter will also be removed in INAV10.0.0.

Improved SD Card support for F7 and H7 flight controllers using SDIO​

This version of INAV fixes some long standing bugs with the SDIO driver for H7 and F765 flight controllers. Now they share the same HAL based driver and fixes. This affects a small number of targets, as most targets use the older and slower SPI based access to SD cards. Moving forward, SDIO is the preferred and recommend way to implement SD Card blackbox in INAV, as it is faster than SPI and support up to 4BIT wide data access, versus SPI 1 bit.

This change affects the following targets:

  • FLYWOOH743PRO
  • IFLIGHT_BLITZ_H7_PRO
  • KAKUTEH7WING
  • MATEKF765
  • MATEKH743
  • MICOAIR743
  • NEUTRONRCH7BT
  • PIXRACER
  • TBS_LUCID_H7

DJI O4 support​

DJI released a new air unit, and while rumors suggested it would include full INAV font support, that is unfortunately not true with the released firmware. There is also a bug on DJI firmware that prevents it from detecting when the flight controller is armed and leaves the air unit stuck in low power mode.

There are two possible workaround for the arming issues:

  1. Turn off low power mode This should work with older INAV versions as well
  2. On INAV 8.0.0, you can type this on the cli: set enable_broken_o4_workaround = ON

With the added workarounds, setup in INAV should be the same as O3.

Other important changes:​

Breaking Changes​

These changes to the firmware will likely break your settings from an earlier version < 8.x.x.

Profile Consolidation​

The profile CLI command has been renamed to control_profile. When updating from an older version of INAV, you will need to edit your diff with these changes:

In INAV version < 8

# profile
profile 1

set fw_p_pitch = 14
set fw_i_pitch = 5
set fw_d_pitch = 5
set fw_ff_pitch = 137
...

Will become

# profile
control_profile 1

set fw_p_pitch = 14
set fw_i_pitch = 5
set fw_d_pitch = 5
set fw_ff_pitch = 137
...

OSD Custom Elements​

If you have previously used OSD Custom Elements. You will need to update the diff for these, so that they continue to work in the same way. The system has been expanded to allow the use of logic condition results and have more numerical variations. To keep your OSD Custom Elements working, you will need to change the element type IDs, if they are 4, 5, 6, or 7. The table below shows the old and new IDs.

Numeric formatOld nameOld IDNew nameNew ID
000CUSTOM_ELEMENT_TYPE_GV_SMALL6CUSTOM_ELEMENT_TYPE_GV_37
00000CUSTOM_ELEMENT_TYPE_GV4CUSTOM_ELEMENT_TYPE_GV_59
0.0CUSTOM_ELEMENT_TYPE_GV_SMALL_FLOAT7CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_110
0000.0CUSTOM_ELEMENT_TYPE_GV_FLOAT5CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_116

Below, you can see the position of the IDs that you need to change if they are 4, 5, 6, or 7.

osd_custom_elements 0 3 0 1 0 0 0 0 0 "FLAPS"
^ ^ ^

CLI​

New / Changed Items​

NameDescription
geozoneManages the geozone data set
control_profileprofile has been renamed to control_profile

Changed Settings​

NameValues
blackbox_deviceNew: FILE (for SITL usage)
debug_modesNew: ADAPTIVE_FILTER, HEADTRACKER, GPS, LULU, SBUS2
dynamic_gyro_notch_modeRemoved: 3D_R, 3D_P, 3D_Y, 3D_RP, 3D_RY, 3D_PY
filter_type_fullNew: LULU
gps_dyn_modelNew: SEA, MOWER
gps_providerRemoved: UBLOX7 (Use UBLOX; version specific capabilities will be auto-detected)
nav_fw_wp_tracking_accuracyNow set distance from waypoint course line in meters rather some arbitrary tracking response value
rangefinder_hardwareNew: TERARANGER_EVO, USD1_V0, NRA
serial_rxNew: SBUS2

New Settings​

NameDescription
disarm_alwaysWhen you switch to Disarm, do so regardless of throttle position. If this Setting is OFF. It will only disarm only when the throttle is low. This is similar to the previous disarm_kill_switch option. Default setting is the same as the old default behaviour. Default: TRUE
enable_broken_o4_workaroundDJI O4 release firmware has a broken MSP DisplayPort implementation. This enables a workaround to restore ARM detection. Default: FALSE
ez_snappinessEzTune snappiness Values: 0 - 100 Default: 0
failsafe_gps_fix_estimation_delayControls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation. Values: -1 - 600 Default: 7
frsky_use_legacy_gps_mode_sensor_idsS.Port telemetry: If ON, send the legacy telemetry IDs for modes (Tmp1) and GNSS (Tmp2). These are old IDs, deprecated, and will be removed in INAV 10.0. Tools and scripts using these IDs should be updated to use the new IDs of 470 for Modes and 480 for GNSS. Default: 'OFF' Default: FALSE
fw_iterm_lock_engage_thresholdDefines error rate (in percents of max rate) when Iterm Lock is engaged when sticks are release. Iterm Lock will stay active until error drops below this number Values: 5 - 25 Default: 10
fw_iterm_lock_rate_thresholdDefines rate percentage when full P I and D attenuation should happen. 100 disables Iterm Lock for P and D term Values: 10 - 100 Default: 40
fw_iterm_lock_time_max_msDefines max time in milliseconds for how long ITerm Lock will shut down Iterm after sticks are release Values: 100 - 1000 Default: 500
geozone_avoid_altitude_rangeAltitude range in which an attempt is made to avoid a geozone upwards Values: 0 - 1000000 Default: 5000
geozone_detection_distanceDistance from which a geozone is detected Values: 0 - 1000000 Default: 50000
geozone_mr_stop_distanceDistance in which multirotors stops before the border Values: 0 - 100000 Default: 15000
geozone_no_way_home_actionAction if RTH with active geozones is unable to calculate a course to home (RTH, EMRG_LAND). Default: RTH
geozone_safe_altitude_distanceVertical distance that must be maintained to the upper and lower limits of the zone. Values: 0 - 10000 Default: 1000
geozone_safehome_as_inclusiveTreat nearest safehome as inclusive geozone Default: FALSE
geozone_safehome_zone_actionFence action for safehome zone (NONE, AVOID, POS_HOLD, RTH). Default: NONE
gimbal_pan_channelGimbal pan rc channel index. 0 is no channel. Values: 0 - 32 Default: 0
gimbal_pan_trimTrim gimbal pan center position. Values: -500 - 500 Default: 0
gimbal_roll_channelGimbal roll rc channel index. 0 is no channel. Values: 0 - 32 Default: 0
gimbal_roll_trimTrim gimbal roll center position. Values: -500 - 500 Default: 0
gimbal_sensitivityGimbal sensitivity is similar to gain and will affect how quickly the gimbal will react. Values: -16 - 15 Default: 0
gimbal_serial_single_uartGimbal serial and headtracker device share same UART. FC RX goes to headtracker device, FC TX goes to gimbal. Default: FALSE
gimbal_tilt_channelGimbal tilt rc channel index. 0 is no channel. Values: 0 - 32 Default: 0
gimbal_tilt_trimTrim gimbal tilt center position. Values: -500 - 500 Default: 0
gyro_adaptive_filter_hpf_hzHigh pass filter cutoff frequency Values: 1 - 50 Default: 10
gyro_adaptive_filter_integrator_threshold_highHigh threshold for adaptive filter integrator Values: 1 - 10 Default: 4
gyro_adaptive_filter_integrator_threshold_lowLow threshold for adaptive filter integrator Values: -10 - 0 Default: -2
gyro_adaptive_filter_max_hzMaximum frequency for adaptive filter Values: 0 - 505 Default: 150
gyro_adaptive_filter_min_hzMinimum frequency for adaptive filter Values: 0 - 250 Default: 50
gyro_adaptive_filter_std_lpf_hzStandard deviation low pass filter cutoff frequency Values: 0 - 10 Default: 2
gyro_adaptive_filter_targetTarget value for adaptive filter Values: 1 - 6 Default: 3.5
gyro_filter_modeSpecifies the type of the software LPF of the gyro signals (OFF, STATIC, DYNAMIC, ADAPTIVE). Default: STATIC
gyro_lulu_enabledEnable/disable gyro LULU filter Default: FALSE
gyro_lulu_sample_countGyro lulu sample count, in number of samples. Values: 1 - 15 Default: 3
headtracker_pan_ratioHead pan movement vs camera movement ratio Values: 0 - 5 Default: 1
headtracker_roll_ratioHead roll movement vs camera movement ratio Values: 0 - 5 Default: 1
headtracker_tilt_ratioHead tilt movement vs camera movement ratio Values: 0 - 5 Default: 1
headtracker_typeType of headtracker dervice (NONE, SERIAL, MSP). Default: NONE
inav_allow_gps_fix_estimationDefines if inav will estimate GPS fix with magnetometer and barometer on GPS outages. Enables navigation and RTH without GPS fix on fixed wing. Also see failsafe_gps_fix_estimation_delay. Default: FALSE
inav_default_alt_sensorSets the default altitude sensor to use (GPS, BARO, GPS_ONLY, BARO_ONLY). Settings GPS and BARO always use both sensors unless there is an altitude error between the sensors that exceeds a set limit. In this case only the selected sensor will be used while the altitude error limit is exceeded. GPS error limit = 2 * inav_max_eph_epv. BARO error limit = 4 * inav_baro_epv. Settings GPS_ONLY and BARO_ONLY will use only the selected sensor even if the other sensor is working. The other sensor will only be used as a backup if the selected sensor is no longer available to use. Default: GPS
inav_w_z_baro_vWeight of barometer climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. Values: 0 - 10 Default: 0.1
mavlink_min_txbufferMinimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits. Values: 0 - 100 Default: 33
mavlink_radio_typeMavlink radio type (GENERIC, ELRS, SIK). Affects how RSSI and LQ are reported on OSD. Default: GENERIC
nav_fw_alt_control_responseAdjusts the deceleration response of fixed wing altitude control as the target altitude is approached. Decrease value to help avoid overshooting the target altitude. Values: 5 - 100 Default: 40
nav_fw_auto_climb_rateMaximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] Values: 10 - 2000 Default: 500
nav_fw_launch_wiggle_to_wake_idleTrigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails. Values: 0 - 2 Default: 0
nav_fw_manual_climb_rateMaximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] Values: 10 - 2500 Default: 300
nav_fw_pos_z_ffFF gain of altitude PID controller (Fixedwing) Values: 0 - 255 Default: 10
nav_mc_auto_climb_rateMaximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] Values: 10 - 2000 Default: 500
nav_mc_inverted_crash_detectionSetting a value > 0 enables inverted crash detection for multirotors. It will auto disarm in situations where the multirotor has crashed inverted on the ground and can't be manually disarmed due to loss of control or for some other reason. When enabled this setting defines the additional number of seconds before disarm beyond a minimum fixed time delay of 3s. Requires a barometer to work. Values: 0 - 15 Default: 0
nav_mc_manual_climb_rateMaximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] Values: 10 - 2000 Default: 200
osd_adsb_distance_alertDistance inside which ADSB data flashes for proximity warning Values: 1 - 64000 Default: 3000
osd_adsb_distance_warningDistance in meters of ADSB aircraft that is displayed Values: 1 - 64000 Default: 20000
osd_adsb_ignore_plane_above_me_limitIgnore adsb planes above, limit, 0 disabled (meters) Values: 0 - 64000 Default: 0
osd_decimals_altitudeNumber of decimals for the altitude displayed in the OSD [3-5]. Values: 3 - 5 Default: 3
osd_decimals_distanceNumber of decimals for distance displayed in the OSD [3-5]. This includes distance from home, total distance, and distance remaining. Values: 3 - 5 Default: 3
osd_estimations_wind_mpsWind speed estimation in m/s Default: FALSE
osd_highlight_djis_missing_font_symbolsShow question marks where there is no symbol in the DJI font to represent the INAV OSD element's symbol. When off, blank spaces will be used. Only relevent for DJICOMPAT modes. Default: TRUE
osd_radar_peers_display_timeTime in seconds to display next peer Values: 1 - 10 Default: 3
osd_stats_show_metric_efficiencyEnabling this option will show metric efficiency statistics on the post flight stats screen. In addition to the efficiency statistics in your chosen units. Default: FALSE

Removed Settings​

NameDescription
control_deadband
cpu_underclock
disarm_kill_switch
dji_workarounds
fw_iterm_limit_stick_position
gyro_anti_aliasing_lpf_type
gyro_hardware_lpf
gyro_main_lpf_type
gyro_use_dyn_lpf
inav_use_gps_no_baro
inav_use_gps_velned
ledstrip_visual_beeper
max_throttle
nav_auto_climb_rate
nav_manual_climb_rate
osd_stats_min_voltage_unit
pidsum_limit
pidsum_limit_yaw

Summary of Changes​

New Contributors​

Full Changelog: https://github.com/iNavFlight/inav/compare/7.1.2...8.0.0