-
Notifications
You must be signed in to change notification settings - Fork 1.5k
7.0.0 Release Notes
Please carefully read all of this document for the best possible experience and safety.
Contact other pilots, share experiences, suggestions and ask for help on:
INAV Discord Server | |
INAV Official on Facebook |
The GPS NMEA protocol is no longer supported. All pilots are required to switch to UBLOX protocol. All modern GPS modules (even as old as from 2015 and earlier) support UBLOX protocol and there is not a single good reason to stick to NMEA nowadays
The FrSky D-series telemetry support has been removed. This applies to legacy D4R receivers and some 3rd party whoop boards
- Download and install the new INAV Configurator 7
- Save to a file the current diff all from the CLI.
- Upgrade to INAV 7 using the Full Erase option in the configurator.
- In case of Analog FPV, upload your OSD font of choice from the OSD tab.
- Go to the CLI again and paste the above-described contents from the file you previously created and write save , press ENTER.
- There are many new, changed, and removed settings. Check carefully that the settings are correct and fix any unrecognized or out-of-range items from the saved configuration.
- You should be ready, explore new 7.0 features, and enjoy!
Please follow the instructions on this page.
INAV now was a function that allows to flexibly assign functions to PWM outputs directly from INAV Configurator.
Specific function AUTO
, MOTORS
or SERVOS
can be assigned to each Timer Group. Then, all outputs from this group will perform this function.
Thanks to this, it's possible to use servos and motors in ways that previously required building a custom targets.
Bear in mind:
- In some rare cases, output assignment migh be different than in INAV 6
- It is not possible to assign function to individual outputs. It's a hardware, not software limitation.
Read more in INAV docs
INAV 7 adds the DMA Burst mode to selected target as ultimately fixes the problem of DSHOT protocol not working on some boards. Pilots do not have to take any actions, DSHOT is just available on previously affected flight controllers. This applies to:
- Matek F405 TE
- SpeedyBee F405 V3
The JETI EXBUS protocol should now not hang the flight controller during operation. The issue was originally fixed in https://github.com/betaflight/betaflight/pull/13130 . Thank you @SteveCEvans and @klutvott123
As mentioned in the Important Notes
section, INAV 7 no longer supports the GPS NMEA protocol. All modern GPS module support one of the UBLOX protocols and as a result pilots must switch to either UBLOX
or UBLOX7
protocol.
A number of improvements have been made to GPS support in INAV 7.
It is now possible to select multiple GPS constellations, and not only Galileo. If your GPS modules does not support a particular combination, it will fallback to no extra constellations.
M10 GPS units will now default to 10Hz, like M8 units and a new cli setting has been added to allow overriding the update rate (gps_ublox_nav_hz
) if you would like to fall back to 5Hz or bump it up to the limits of what is supported by your ublox GPS module.
INAV now support MSP VTX when using MSP DisplayPort OSD.
Now it is possible to change VTX power levels and channels via INAV's OSD menu or ELRS backpack without connecting the SmartAudio wire on HD-Zero VTXs.
If you MSP DisplayPort OSD is working, no extra configuration is needed.
- The
AUTOLEVEL
mode is renamed toAUTO LEVEL TRIM
- FrSky D-series telemetry
-
output_mode
setting that allows to reassign all PWM outputs to either MOTORS or SERVOS
- SDmodel H7V1
- Matek H743HD
- SpeedyBee F405 V4
- SpeedeBee F405 Mini
- SpeedyBee F2 Mini V2
- GEPRCF405
- GEPRCF722
- NEUTRONRC F435 Mini AIO
Name | Description |
---|---|
gps_provider | Removed: NMEA
|
gps_sbas_mode | New: SPAN
|
nav_rth_alt_mode | Removed: AT_LEAST_LINEAR_DESCENT
|
pitot_hardware | New: DLVR-L10D
|
Name | Description |
---|---|
ez_aggressiveness | EzTune aggressiveness Values: 0 - 200 Default: 100 |
ez_axis_ratio | EzTune axis ratio Values: 25 - 175 Default: 110 |
ez_damping | EzTune damping Values: 0 - 200 Default: 100 |
ez_enabled | Enables EzTune feature Default: FALSE |
ez_expo | EzTune expo Values: 0 - 200 Default: 100 |
ez_filter_hz | EzTune filter cutoff frequency Values: 10 - 300 Default: 110 |
ez_rate | EzTune rate Values: 0 - 200 Default: 100 |
ez_response | EzTune response Values: 0 - 200 Default: 100 |
ez_stability | EzTune stability Values: 0 - 200 Default: 100 |
gps_auto_baud_max_supported | Max baudrate supported by GPS unit. This is used during autobaud. M8 supports up to 460400, M10 supports up to 921600 and 230400 is the value used before INAV 7.0 Default: 230400 |
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. Values: 5 - 200 Default: 10 |
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: FALSE |
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: FALSE |
led_pin_pwm_mode | PWM mode of LED pin. Values: SHARED_LOW , SHARED_HIGH , LOW , HIGH . Default: SHARED_LOW
|
mixer_automated_switch | If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type Default: FALSE |
mixer_pid_profile_linking | If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup. Default: FALSE |
mixer_switch_trans_timer | If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch. Values: 0 - 200 Default: 0 |
motorstop_on_low | If enabled, motor will stop when throttle is low on this mixer_profile Default: FALSE |
nav_cruise_yaw_rate | Max YAW rate when NAV COURSE HOLD/CRUISE mode is enabled. Set to 0 to disable on fixed wing (Note: On multirotor setting to 0 will disable Course Hold/Cruise mode completely) [dps] Values: 0 - 120 Default: 20 |
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: FALSE |
nav_mc_althold_throttle | If set to STICK the FC remembers the throttle stick position when enabling ALTHOLD and treats it as the neutral midpoint for holding altitude. If set to MID_STICK or HOVER the neutral midpoint is set to the mid stick position or the hover throttle position respectively. Default: STICK |
nav_rth_linear_descent_start_distance | The distance [m] away from home to start the linear descent. 0 = immediately (original linear descent behaviour) Values: 0 - 10000 Default: 0 |
nav_rth_use_linear_descent | If enabled, the aircraft will gradually descent to the nav_rth_home_altitude en route. The distance from home to start the descent can be set with nav_rth_linear_descent_start_distance . Default: FALSE |
osd_arm_screen_display_time | Amount of time to display the arm screen [ms] Values: 1000 - 5000 Default: 1500 |
osd_inav_to_pilot_logo_spacing | The space between the INAV and pilot logos, if osd_use_pilot_logo is ON . This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen. Values: 0 - 20 Default: 8 |
osd_joystick_down | PWM value for DOWN key Values: 0 - 100 Default: 0 |
osd_joystick_enabled | Enable OSD Joystick emulation Default: FALSE |
osd_joystick_enter | PWM value for ENTER key Values: 0 - 100 Default: 75 |
osd_joystick_left | PWM value for LEFT key Values: 0 - 100 Default: 63 |
osd_joystick_right | PWM value for RIGHT key Values: 0 - 100 Default: 28 |
osd_joystick_up | PWM value for UP key Values: 0 - 100 Default: 48 |
osd_mah_precision | Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity Values: 4 - 6 Default: 4 |
osd_use_pilot_logo | Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511 Default: FALSE |
pid_iterm_limit_percent | Limits max/min I-term value in stabilization PID controller. It solves the problem of servo saturation before take-off/throwing the airplane into the air. Or multirotors with low authority. By default, error accumulated in I-term can not exceed 33% of total pid throw (around 165us on deafult pidsum_limit of pitch/roll). Set 0 to disable completely. Values: 0 - 200 Default: 33 |
tpa_on_yaw | Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors. Default: FALSE |
Name | Description |
---|---|
dterm_lpf2_hz | |
dterm_lpf2_type | |
frsky_coordinates_format | |
frsky_default_latitude | |
frsky_default_longitude | |
frsky_unit | |
frsky_vfas_precision | |
fw_iterm_throw_limit | |
moron_threshold | |
nav_fw_cruise_yaw_rate | |
nav_use_midthr_for_althold | |
osd_mah_used_precision | |
output_mode |
The full list of changes is available here The full list of INAV Configurator changes is available here
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
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
Failsafe
Failsafe
DevDocs Failsafe.md
PID Tuning
EZ-Tune
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
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 Tuning
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