Skip to content

3.0.0 Release Notes

Jonathan Hudson edited this page May 9, 2021 · 38 revisions

Hello and welcome to INAV 3.0.0 Release!

Please carefully read all of this document for the best possible experience and safety.

Get in touch with other pilots, share experiences, suggestions and ask for help on:

INAV Official on Telegram
INAV Official on Facebook

Please continue to support developers, for free, by checking out from the following stores after having clicked on the following links:

Support us on Banggood

Your contribution from the past month has been very welcome! Thanks!

Tested and suggested hardware can be found here

Important Notes

F3 Removal

STM32 F3 flight controllers like Omnibus F3 or SP Racing F3 are no longer supported in INAV. If you are still using F3 boards, please migrate to F4 or F7.

The supporting code will be retained for a few more releases, but will not be maintained and is not guaranteed to build or work properly in the future.

Adjustments

There are now separate adjustments for D and CD/FF gains. This breaks compatibility with diffs from previous releases. Check the adjustments tab in the configurator after restoring a diff to makes sure they are set up correctly.

Font update required

The OSD fonts have been improved (@Jettrel) and there are several new symbols. Therefore, a font file update is required. Load the updated font of your choosing from the OSD tab.

Upgrading from 2.6, 2.6.1

  1. Download and install the new configurator
  2. Save to a file the current diff all from the CLI.
  3. Upgrade to INAV 3.0 using the Full Erase option in the configurator.
  4. Upload your OSD font of choice from the OSD tab.
  5. Go the CLI again and paste the contents on the file you previously created and write save , press ENTER.
  6. There are a large number of new, changed and removed settings. Check carefully that the settings are correct and fix any unrecognised or out of range items from the saved configuration.
  7. You should be ready, explore new 3.0 features and enjoy!

Upgrading from 2.5 or older version

Please follow the instructions on this page.

New targets:

  • Diatone MambaF405US_I2C
  • FLYWOOF411_V2
  • Mamba F722_I2C

CLI:

New commands

None (TBC).

Changed Settings

Setting Description
blackbox_device Default: target
log_level Default: ERROR
nav_overrides_motor_stop When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV
nav_rth_climb_first New: ON_FW_SPIRAL
platform_type Default: MULTIROTOR
receiver_type Default: target
rssi_source Default: AUTO

New Settings

Setting Description
dji_speed_source Sets the speed type displayed by the DJI OSD: GROUND, 3D, AIR Default: GROUND
dshot_beeper_enabled Whether using DShot motors as beepers is enabled Default: TRUE
dshot_beeper_tone Sets the DShot beeper tone Values: 1 - 5 Default: 1
fw_d_pitch Fixed wing rate stabilisation D-gain for PITCH Default: 0
fw_d_roll Fixed wing rate stabilisation D-gain for ROLL Default: 0
fw_d_yaw Fixed wing rate stabilisation D-gain for YAW Default: 0
fw_level_pitch_trim Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level Values: -10 - 10 Default: 0
fw_yaw_iterm_freeze_bank_angle Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled. Values: 0 - 90 Default: 0
gyro_abg_alpha Alpha factor for Gyro Alpha-Beta-Gamma filter Values: 0 - 1 Default: 0
gyro_abg_boost Boost factor for Gyro Alpha-Beta-Gamma filter Values: 0 - 2 Default: 0.35
gyro_abg_half_life Sample half-life for Gyro Alpha-Beta-Gamma filter Values: 0 - 10 Default: 0.5
gyro_anti_aliasing_lpf_hz Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz Values: 0 - 255 Default: 250
gyro_anti_aliasing_lpf_type Specifies the type of the software LPF of the gyro signals. Default: PT1
gyro_dyn_lpf_curve_expo Expo value for the throttle-to-frequency mapping for Dynamic LPF Values: 1 - 10 Default: 5
gyro_dyn_lpf_max_hz Maximum frequency of the gyro Dynamic LPF Values: 40 - 1000 Default: 500
gyro_dyn_lpf_min_hz Minimum frequency of the gyro Dynamic LPF Values: 40 - 400 Default: 200
gyro_main_lpf_hz Software based gyro main lowpass filter. Value is cutoff frequency (Hz) Values: 0 - 500 Default: 60
gyro_main_lpf_type Defines the type of the main gyro LPF filter. Possible values: PT1, BIQUAD. PT1 offers faster filter response while BIQUAD better attenuation. Default: BIQUAD
gyro_use_dyn_lpf Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position. Default: FALSE
imu2_align_pitch Pitch alignment for Secondary IMU. 1/10 of a degree Values: -1800 - 3600 Default: 0
imu2_align_roll Roll alignment for Secondary IMU. 1/10 of a degree Values: -1800 - 3600 Default: 0
imu2_align_yaw Yaw alignment for Secondary IMU. 1/10 of a degree Values: -1800 - 3600 Default: 0
imu2_gain_acc_x Secondary IMU ACC calibration data Values: -32768 - 32767 Default: 0
imu2_gain_acc_y Secondary IMU ACC calibration data Values: -32768 - 32767 Default: 0
imu2_gain_acc_z Secondary IMU ACC calibration data Values: -32768 - 32767 Default: 0
imu2_gain_mag_x Secondary IMU MAG calibration data Values: -32768 - 32767 Default: 0
imu2_gain_mag_y Secondary IMU MAG calibration data Values: -32768 - 32767 Default: 0
imu2_gain_mag_z Secondary IMU MAG calibration data Values: -32768 - 32767 Default: 0
imu2_hardware Selection of a Secondary IMU hardware type. NONE disables this functionality Default: NONE, values NONE, BNO055, BNO055_SERIAL
imu2_radius_acc Secondary IMU MAG calibration data Values: -32768 - 32767 Default: 0
imu2_radius_mag Secondary IMU MAG calibration data Values: -32768 - 32767 Default: 0
imu2_use_for_osd_ahi If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon Default: FALSE
imu2_use_for_osd_heading If set to ON, Secondary IMU data will be used for Analog OSD heading Default: FALSE
imu2_use_for_stabilized If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH) Default: FALSE
mavlink_version Version of MAVLink to use Values: 1 - 2 Default: 2
nav_land_maxalt_vspd Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s] Values: 100 - 2000 Default: 200
nav_land_minalt_vspd Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s] Values: 50 - 500 Default: 50
nav_max_altitude Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled Values: 0 - 65000 Default: 0
nav_mc_wp_slowdown When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes. Default: TRUE
nav_rth_alt_control_override If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the RTH climb phase using full pitch or roll stick held for > 1 second. RTH altitude is reset to the current altitude using pitch down stick. RTH CLIMB FIRST is overridden using right roll stick so craft turns and heads directly to home (CLIMB FIRST override only works for fixed wing) Default: FALSE
osd_pan_servo_index Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. Values: 0 - 10 Default: 0
osd_pan_servo_pwm2centideg Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs 18 for this setting. Change sign to inverse direction. Values: -36 - 36 Default: 0
osd_plus_code_short Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates. Default: 0
osd_sidebar_height Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) Values: 0 - 5 Default: 3
osd_stats_min_voltage_unit Display minimum voltage of the BATTERY or the average per CELL in the OSD stats. Default: BATTERY. Options BATTERY, CELL
osd_telemetry To enable OSD telemetry for antenna tracker. Possible values are OFF, ON and TEST Default: OFF
prearm_timeout Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. Values: 0 - 10000 Default: 10000
safehome_max_distance In order for a safehome to be used, it must be less than this distance (in cm) from the arming point. Values: 0 - 65000 Default: 20000
safehome_usage_mode Used to control when safehomes will be used. Possible values are OFF, RTH and RTH_FS. See Safehome documentation for more information. Default: RTH
servo_autotrim_rotation_limit Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using feature FW_AUTOTRIM. Values: 1 - 60 Default: 15
smith_predictor_delay Expected delay of the gyro signal. In milliseconds Values: 0 - 8 Default: 0
smith_predictor_lpf_hz Cutoff frequency for the Smith Predictor Low Pass Filter Values: 1 - 500 Default: 50
smith_predictor_strength The strength factor of a Smith Predictor of PID measurement. In percents Values: 0 - 1 Default: 0.5
turtle_mode_power_factor Turtle mode power factor Values: 0 - 100 Default: 55
vtx_smartaudio_early_akk_workaround Enable workaround for early AKK SAudio-enabled VTX bug. Default: TRUE

Removed settings

Setting Description
gyro_lpf_hz
gyro_lpf_type
gyro_stage2_lowpass_hz
gyro_stage2_lowpass_type
gyro_sync
nav_landing_speed replaced by nav_land_minalt_vspd and nav_land_maxalt_vspd

Renamed settings

Old name New name
mc_airmode_threshold airmode_threshold
mc_airmode_type airmode_type
osd_artificial_horizon_max_pitch osd_ahi_max_pitch
osd_artificial_horizon_reverse_roll osd_ahi_reverse_roll

New drivers and protocols

  • Rangefinder "GY-US42(v2) Ultrasonic Range Sensor
  • Rangefinder vl53l1x
  • BNO055 Secondary IMU
  • BMI088 IMU

New features

Turtle mode aka Flip Over after crash (@kernel-machine)

inav now has a "Turtle Mode".

  • Requires DSHOT ESC protocol
  • Assign a switch to TURTLE mode
  • Ensure you can arm at any angle

WP mission sealevel altitude datum (@breadoven)

Prior to inav 3.0, mission waypoint altitudes are relative the arming location. It is now possible to define waypoints with absolute (AMSL) altitude, making the mission independent of the arming location. See the inav wiki for details (WP paramater 3)

WP Mission Landing Elevation Setting (@breadoven)

The relative / absolute ground altitude of a LAND waypoint may be set as WP paramater 2 (m). See the inav wiki for details.

Do not slow down in WP mission when approaching a waypoint (@DzikuVx)

DShot Beeper (@harry1453)

RC via MAVLink & MAVLink V2 Support (@harry1453)

Prearm Mode (@harry1453)

Prearm offers a two-stage arming process as an optional additional safety feature.

  • Activate prearm (normally a button or momentary switch)
  • Activate arm

Initial cut on H7 MCU support (@digitalentity, @bkleiner, @DzikuVx)

H7 is available in the source repository; target Hex files will be released as targets mature, probably in the future point releases.

Add D-term to control loop on fixed wing aircraft (@avsaase)

Improvements and updates

Gyro processing improvements (@DzikuVx)

Update EGNOS PRN mask to latest EGSA definition, fix SBAS for non-Galileo usage (@stronnag)

The EGNOS (GPS ground assistance) definitions have been updated to the latest values for all GNSS options. An invalid association with availability of Galileo has been corrected.

Make CW270FLIP default MAG alignment (@DzikuVx)

New FCs raraly feature on-board compass, and most GPS+MAG default to CW270FLIP, so this is now the inav default. If you use another value, check your setup after upgrading.

Add CRUISE mode which is equivalent to CRSH+AH (@shellixyz)

Add option to display min cell voltage instead of min pack voltage on the disarm screen (@avsaase)

Bump OSD font min version to 2 (@shellixyz)

Multirotors: add new setting for final landing vertical speed instead of being hard-coded to 25% of set landing vertical speed (@shellixyz)

Drop gyro_sync (@DzikuVx)

Delayed safehome (@tonyyng)

Safehome does not now replace the arming location until it is needed. If you cancel RTH or recover from RX failsafe, the original arming location is restored as the home location. Under normal circumstances, "distance to home" will revert to range from the arming location.

Switched RTH Preset Altitude Override (@breadoven)

Provides stick options to override configured RTH climb and/or turn behaviour. See the nav_rth_alt_control_override setting description for details.

Renamed OSD SW and LEDLOW to OSD/LEDS OFF (@MrD-RC)

Fixed wing RTH Spiral Climb Option (@breadoven)

Increase loiter max radius to 300m (@DzikuVx)

Rename NAV CRUISE mode to NAV COURSE HOLD (@shellixyz)

Homogenize OSD AHI settings prefix (@shellixyz)

Do not slow down in WP mission when approaching a waypoint (@DzikuVx)

Configure speed source for DJI OSD (@DzikuVx)

Pan servo home direction offset (@avsaase)

Increased fw loiter radius default (@MrD-RC)

Ability to trim pitch angle for level flight (@DzikuVx)

vtx_smartaudio_early_akk_workaround option (@RomanLut)

Added option to output servos on PWM and SBUS (@IVData)

build: Use -Os for F7 targets with flash <= 512K (@fiam)

Option for local plus codes on osd (@avsaase)

This adds the option to remove the first 2, 4, or 6 digits from the OSD plus code. Doing so requires a reference location (for example your current location when using Google Maps on your phone) within ~600, ~40, and ~2km, respectively.

Changed default settings for fixed wing throttle smoothing in navigation modes (@Airwide)

Throttle smoothing in the navigation modes on fixed wing aircraft is now enabled by default. This results in smoother throttle management and more efficient cruising.

Disable all F3 targets (@DzikuVx)

FrSky Pixel OSD: Honor ahi_max_pitch when drawing the horizon line (@fiam, @shellixyz)

All Changes since 2.6.1

WIKI TOPICS

Wiki Home Page

INAV Version Release Notes

7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes

QUICK START GUIDES

Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md

Connecting to INAV

Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\

Flashing and Upgrading

Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md

Setup Tab
Live 3D Graphic & Pre-Arming Checks

Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration

Alignment Tool Tab
Adjust mount angle of FC & Compass

Ports Tab
Map Devices to UART Serial Ports

Receiver Tab
Set protocol and channel mapping

Mixer

Mixer Tab
Custom mixes for exotic setups
DevDocs Mixer.md

Outputs

DevDocs ESC and servo outputs.md
DevDocs Servo.md

Modes

Modes
Navigation modes
Navigation Mode: Return to Home
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md

Configuration

Sensor auto detect and hardware failure detection

Failsafe

Failsafe
DevDocs Failsafe.md

PID Tuning

PID Attenuation and scaling
Fixed Wing Tuning for INAV 3.0
Tune INAV PIFF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md

GPS

GPS and Compass setup
GPS Failsafe and Glitch Protection

OSD and VTx

DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md

LED Strip

DevDocs LedStrip.md

ADVANCED

Advanced Tuning

Fixed Wing Autolaunch
DevDocs INAV_Autolaunch.pdf

Programming

DevDocs Programming Framework.md

Adjustments

DevDocs Inflight Adjustments.md

Mission Control

iNavFlight Missions
DevDocs Safehomes.md

Tethered Logging

Log when FC is connected via USB

Blackbox

DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md

CLI

iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md

VTOL

DevDocs MixerProfile.md
DevDocs VTOL.md

TROUBLESHOOTING

"Something" is disabled Reasons
Blinkenlights
Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane

ADTL TOPICS, FEATURES, DEV INFO

AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Features safe to add and remove to fit your needs.
Developer info
INAV MSP frames changelog
INAV Remote Management, Control and Telemetry
Lightweight Telemetry (LTM)
Making a new Virtualbox to make your own INAV
MSP Navigation Messages
MSP V2
OrangeRX LRS RX and OMNIBUS F4
Rate Dynamics
Target and Sensor support
UAV Interconnect Bus
Ublox 3.01 firmware and Galileo
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md

OLD LEGACY INFO

Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
iNav Telemetry
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md

Clone this wiki locally