WaF Bot Posté(e) Janvier 21 Signaler Posté(e) Janvier 21 Hello and welcome to INAV 8.0.0 "Gallant Goshawk" 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 INAV 8 no longer includes F411 targets as part of the official release. 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. 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 None Upgrading from a previous release Upgrading from INAV 7.0 and 7.1 Backup configuration with CLI diff all command Download and install the new INAV Configurator 8.0 Flash INAV 8.0 WITH Full Chip Erase option enabled Edit the 7.x diff and apply Diff breaking changes described bellow, and save it as your new inav 8 diff. See Diff breaking changes section below. Select Keep current settings from the defaults pop-up Go to CLI and restore your edited inav diff Done This tool can help migrate your INAV 7.x diff over to INAV 8.0.0. It will take care of the major changes that have been highlighted in these release notes. Upgrading from older versions Please follow the instructions on this page. 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. Mavlink Advancement for MavlinkRC 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 Users can change the precision (amount of decimal places) for Altitude and Distance #10431 Enhancements for Custom OSD Elements #10282 Update arming screen for better space utilisation #10300 OSD system message improvements #10090 Better organisation of the post flight stats screen with more stats available #9617 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: Turn off low power mode This should work with older INAV versions as well 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: Multirotor inverted crash detection #10099 Waypoint tracking improvements #10278 (Note usage change for nav_fw_wp_tracking_accuracy may require change of setting) Fixed wing altitude velocity control #9471 (see know issues above related to this change) Diff breaking changes 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 this change. For example: # 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 format Old name Old ID New name New ID 000 CUSTOM_ELEMENT_TYPE_GV_SMALL 6 CUSTOM_ELEMENT_TYPE_GV_3 7 00000 CUSTOM_ELEMENT_TYPE_GV 4 CUSTOM_ELEMENT_TYPE_GV_5 9 0.0 CUSTOM_ELEMENT_TYPE_GV_SMALL_FLOAT 7 CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1 10 0000.0 CUSTOM_ELEMENT_TYPE_GV_FLOAT 5 CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1 16 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 Name Description geozone Manages the geozone data set control_profile profile has been renamed to control_profile Changed Settings Name Values blackbox_device New: FILE (for SITL usage) debug_modes New: ADAPTIVE_FILTER, HEADTRACKER, GPS, LULU, SBUS2 dynamic_gyro_notch_mode Removed: 3D_R, 3D_P, 3D_Y, 3D_RP, 3D_RY, 3D_PY filter_type_full New: LULU gps_dyn_model New: SEA, MOWER gps_provider Removed: UBLOX7 (Use UBLOX; version specific capabilities will be auto-detected) nav_fw_wp_tracking_accuracy Now set distance from waypoint course line in meters rather some arbitrary tracking response value rangefinder_hardware New: TERARANGER_EVO, USD1_V0, NRA serial_rx New: SBUS2 New Settings Name Description disarm_always When 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_workaround DJI O4 release firmware has a broken MSP DisplayPort implementation. This enables a workaround to restore ARM detection. Default: FALSE ez_snappiness EzTune snappiness Values: 0 - 100 Default: 0 failsafe_gps_fix_estimation_delay Controls 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_ids S.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_threshold Defines 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_threshold Defines 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_ms Defines 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_range Altitude range in which an attempt is made to avoid a geozone upwards Values: 0 - 1000000 Default: 5000 geozone_detection_distance Distance from which a geozone is detected Values: 0 - 1000000 Default: 50000 geozone_mr_stop_distance Distance in which multirotors stops before the border Values: 0 - 100000 Default: 15000 geozone_no_way_home_action Action if RTH with active geozones is unable to calculate a course to home (RTH, EMRG_LAND). Default: RTH geozone_safe_altitude_distance Vertical distance that must be maintained to the upper and lower limits of the zone. Values: 0 - 10000 Default: 1000 geozone_safehome_as_inclusive Treat nearest safehome as inclusive geozone Default: FALSE geozone_safehome_zone_action Fence action for safehome zone (NONE, AVOID, POS_HOLD, RTH). Default: NONE gimbal_pan_channel Gimbal pan rc channel index. 0 is no channel. Values: 0 - 32 Default: 0 gimbal_pan_trim Trim gimbal pan center position. Values: -500 - 500 Default: 0 gimbal_roll_channel Gimbal roll rc channel index. 0 is no channel. Values: 0 - 32 Default: 0 gimbal_roll_trim Trim gimbal roll center position. Values: -500 - 500 Default: 0 gimbal_sensitivity Gimbal sensitivity is similar to gain and will affect how quickly the gimbal will react. Values: -16 - 15 Default: 0 gimbal_serial_single_uart Gimbal serial and headtracker device share same UART. FC RX goes to headtracker device, FC TX goes to gimbal. Default: FALSE gimbal_tilt_channel Gimbal tilt rc channel index. 0 is no channel. Values: 0 - 32 Default: 0 gimbal_tilt_trim Trim gimbal tilt center position. Values: -500 - 500 Default: 0 gyro_adaptive_filter_hpf_hz High pass filter cutoff frequency Values: 1 - 50 Default: 10 gyro_adaptive_filter_integrator_threshold_high High threshold for adaptive filter integrator Values: 1 - 10 Default: 4 gyro_adaptive_filter_integrator_threshold_low Low threshold for adaptive filter integrator Values: -10 - 0 Default: -2 gyro_adaptive_filter_max_hz Maximum frequency for adaptive filter Values: 0 - 505 Default: 150 gyro_adaptive_filter_min_hz Minimum frequency for adaptive filter Values: 0 - 250 Default: 50 gyro_adaptive_filter_std_lpf_hz Standard deviation low pass filter cutoff frequency Values: 0 - 10 Default: 2 gyro_adaptive_filter_target Target value for adaptive filter Values: 1 - 6 Default: 3.5 gyro_filter_mode Specifies the type of the software LPF of the gyro signals (OFF, STATIC, DYNAMIC, ADAPTIVE). Default: STATIC gyro_lulu_enabled Enable/disable gyro LULU filter Default: FALSE gyro_lulu_sample_count Gyro lulu sample count, in number of samples. Values: 1 - 15 Default: 3 headtracker_pan_ratio Head pan movement vs camera movement ratio Values: 0 - 5 Default: 1 headtracker_roll_ratio Head roll movement vs camera movement ratio Values: 0 - 5 Default: 1 headtracker_tilt_ratio Head tilt movement vs camera movement ratio Values: 0 - 5 Default: 1 headtracker_type Type of headtracker dervice (NONE, SERIAL, MSP). Default: NONE inav_allow_gps_fix_estimation Defines 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_sensor Sets 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_v Weight 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_txbuffer Minimum 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_type Mavlink radio type (GENERIC, ELRS, SIK). Affects how RSSI and LQ are reported on OSD. Default: GENERIC nav_fw_alt_control_response Adjusts 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_rate Maximum 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_idle Trigger 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_rate Maximum 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_ff FF gain of altitude PID controller (Fixedwing) Values: 0 - 255 Default: 10 nav_mc_auto_climb_rate Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] Values: 10 - 2000 Default: 500 nav_mc_inverted_crash_detection Setting 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_rate Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] Values: 10 - 2000 Default: 200 osd_adsb_distance_alert Distance inside which ADSB data flashes for proximity warning Values: 1 - 64000 Default: 3000 osd_adsb_distance_warning Distance in meters of ADSB aircraft that is displayed Values: 1 - 64000 Default: 20000 osd_adsb_ignore_plane_above_me_limit Ignore adsb planes above, limit, 0 disabled (meters) Values: 0 - 64000 Default: 0 osd_decimals_altitude Number of decimals for the altitude displayed in the OSD [3-5]. Values: 3 - 5 Default: 3 osd_decimals_distance Number 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_mps Wind speed estimation in m/s Default: FALSE osd_highlight_djis_missing_font_symbols Show 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_time Time in seconds to display next peer Values: 1 - 10 Default: 3 osd_stats_show_metric_efficiency Enabling 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 Name Description 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 What's Changed bf2inav.py: clearer error messages, number PWM outputs by @sensei-hacker in #9611 Multirotor landing G bump detection improvements by @breadoven in #10138 Include trusted altitude for healthy position estimation by @breadoven in #10083 [crsf] move LAND flight mode into ARMED section by @stronnag in #10139 Attempt at building master on sucessfull push by @mmosca in #10131 Update dev-builds.yml by @mmosca in #10146 Change tag for nightly builds by @mmosca in #10149 Programming framework doc - loiter radius by @sensei-hacker in #10151 Update release notes with recommendation fro full chip erase. by @mmosca in #10152 OSD system message improvements by @breadoven in #10090 Remove unused and commented out function from osd.c by @rmaia3d in #10147 Update dev-builds.yml by @0crap in #10153 Add link to nightly builds by @mmosca in #10155 Walksnail Serial gimbal and headtracker support by @mmosca in #10109 Update readme.md by @0crap in #10160 Inhibit active failsafe procedures on landing detection by @breadoven in #10135 Multirotor inverted crash detection by @breadoven in #10099 Update Controls.md by @MrD-RC in #10163 Update nav config revision number by @breadoven in #10162 Don't run biulds for documentation only changes by @mmosca in #10164 Add ICM42688-G to IFLIGHTF4_SUCCEXD by @DzikuVx in #10161 Further serial gimbal/headtracker improvements by @mmosca in #10159 bind_rx cli command now supports CRSF based receivers by @mmosca in #10166 Update bind_rx cli documentation by @mmosca in #10170 Update Cli.md by @mmosca in #10171 Only generate nightly build release if the change includes code. by @mmosca in #10172 Fixed position for formation flight / inav radar by @error414 in #9883 Add msp command to send raw ublox commands to gps by @mmosca in #9349 Allow SBUS servo protocol to output 18 channels, expand mixer to up to 24 channels by @mmosca in #10165 [Targets] USE_MAG_ALL by @mmosca in #10176 Gyro LULU smoother as gyro filter alternative by @DzikuVx in #10177 LULU filter port to iNav as a single replacement for most filters in iNav, simplifying filter configuration drastically by @pjpei in #10145 [FIX] BMI088 driver: get BMI088 acc aligned by @Minderring in #10174 Add ICM-42688P to KakuteF4 by @jamming in #10175 Remove of register optimization in favor or relying on GCC optimization. by @DzikuVx in #10178 Add some docs on Serial Gimbal by @mmosca in #10182 Add flown loiter radius to programming logic by @breadoven in #10183 [GPS] Fix message rate for newer ublox devices and add some extra debugging features by @mmosca in #10179 Fixed position for formation flight / inav radar by @P-I-Engineer in #10190 mixer.h: PLATFORM_OTHER isn't valid, remove by @sensei-hacker in #10201 Fix typo in Rx doc.md by @RobertoD91 in #10202 [GPS] Fix GPS dynamic model setup for M10 GPS units by @mmosca in #10199 Add UBLOX PSA to README by @mmosca in #10204 [gps] correct version checks by @mmosca in #10205 IFLIGHT_BLITZ_ATF435 MAX_PWM_OUTPUT_PORTS should 8 by @sensei-hacker in #10206 Make LULU smoother independent from the gyro LPF by @DzikuVx in #10186 Update OSD.md - List all of the OSD-related docs by @sensei-hacker in #10212 [GPS] Add SEA and MOWER dynamic models. by @mmosca in #10211 [GPS] UBLOX and UBLOX7 have been merged into UBLOX by @mmosca in #10214 Update gps_provider documentaion by @mmosca in #10220 create single zip with all hex files, again. by @mmosca in #10221 All all baro to IFLIGHTF4_SUCCEXD by @DzikuVx in #10218 Improve MAVLink behavior with flow control capable links by @MUSTARDTIGERFPV in #10222 Add blackbox device FILE for SITL build by @bartslinger in #10228 GEPRC_F722_AIO include UART3 by @sensei-hacker in #10233 Add new targets: MicoAir405Mini, MicoAir405v2 and MicoAir743 by @Minderring in #10198 Add gyros to DakeFPV targets by @DzikuVx in #10242 Add a new target KakuteF4wing by @jamming in #10122 Inflight timer fix by @breadoven in #10245 SBUS2 telemetry support by @mmosca in #10169 Fix programming framework parameters using int16 instead of in32 by @MrD-RC in #10246 Lower sbus2 telemetry task priority by @mmosca in #10250 Make sure DEFAULT_I2C_DEVICE is always valid by @mmosca in #10253 Nav course hold yaw stick control improvement for fixed wing by @breadoven in #10187 Change MAVLink component ID to be a "proper" autopilot by @MUSTARDTIGERFPV in #10258 Increase SMARTAUDIO_MAX_POWER_COUNT to 8 by @bkleiner in #10261 add additional BBL headers for MAX SERVO increase by @stronnag in #10263 only BBL log servos defined in the mixer by @stronnag in #10267 add SERVOS to blackbox optional fields list by @stronnag in #10272 Allow serialpassthrough to set parity & stop bits by @MUSTARDTIGERFPV in #10271 Refactor sbus to support futaba's FASSTest26 sbus2 mode (Potentially 36 channels) by @mmosca in #10270 Fix mixer tab by @mmosca in #10277 Allow number of servos exceed pwm outputs, if servo protocol is sbus_pwm by @mmosca in #10276 Allow Mission Upload mid flight by @b14ckyy in #10273 cli.c: Add reason for Navigation Unsafe to status by @sensei-hacker in #10280 AOCODARCF7MINI_V1: DSHOT_DMAR and V1 output order by @sensei-hacker in #10260 Support SBUS2 FASSTest 12 channel short frame time by @mmosca in #10288 add h7 svd file by @bkleiner in #10289 Mac-OS wiki update | How to connect to configurator by @KY-S0ong in #10279 vtx: fix VTX_SETTINGS_POWER_COUNT by @bkleiner in #10290 Jh fix bbl servo logging by @stronnag in #10303 remove excessive SD debug from MSP processing by @stronnag in #10306 adsb enhanced by @error414 in #10298 Add AIKONF7 target by @mbainrot in #9603 Add FLYWOOH743PRO Target by @flywoo in #10285 Update Fixed Wing Landing.md by @b14ckyy in #10311 Update Fixed Wing Landing.md by @b14ckyy in #10312 add TBS_LUCID_FC target by @bkleiner in #10292 add stick_center note to vtol/mixer profile docs for 4+1 motor vtol configurations. by @P-I-Engineer in #10313 GEPRC_F722_AIO add target with UART3 instead of i2c by @sensei-hacker in #10310 MAMBAF722_2022B: use DMAR for motor 7 by @sensei-hacker in #10309 tbs-lucid: remove in-accessible servo pins by @bkleiner in #10332 Change Waypoint mode linear climb method by @breadoven in #10334 Waypoint tracking improvements by @breadoven in #10278 MSP headtracker parsing change by @mmosca in #10342 Update USB Flashing.md - mention using a hub with USB-C by @sensei-hacker in #10343 iFlight IFLIGHT_BLITZ_H7_WING changes by @DzikuVx in #10341 Update ci.yml by @mmosca in #10344 Use all cores during ci builds by @mmosca in #10337 Small fixes for serial gimbal by @mmosca in #10345 at32: add uart pinswap by @bkleiner in #10333 Added documentation about GVARs, PIDFF Controllers, & Integer Math by @trailx in #10335 Update Settings.yaml and settings.md to include units for nav_max_terrain_follow_alt by @daijoubu in #10352 Change SmartPort sensor IDs for GPS and Modes by @MrD-RC in #9868 Enhance OSD Custom Elements by @MrD-RC in #10282 fixed altitude estimator error estimation by @RomanLut in #10367 Update FLYWOOF745 config.c by @flywoo in #10368 [Fix] Potential stack smash in gforce OSD statistics by @Scavanger in #10358 tbs_lucid: mask PA13/PA14 to enable debugging by @bkleiner in #10365 lucid: use PC5 as adc, use PA13/PA14 as PINIO by @bkleiner in #10378 at32: add abilty to specify uart af by @bkleiner in #10366 Change bus for built-in compass for MICOAIR743 target by @bfmvsa in #10384 MICOARI743 Add alternative target that looks for compass on external connector by @mmosca in #10385 Further tweaks to mavlink by @mmosca in #10215 Switch parameters with battery capacity unit by @MrD-RC in #10389 Nav velocity Z estimation improvements by @breadoven in #10243 Navigation.md - Remove outdated references to inav_use_gps_no_baro by @sensei-hacker in #10408 Default altitude sensor setting fix by @breadoven in #10411 Fix lockup on disarm when wh used in post-flight stats by @MrD-RC in #10413 Add MSP command to get ESC telemetry by @jeffhendrix in #10388 Add PrincipioIoT F7 target by @DzikuVx in #10422 at32: add ability to specify uart rx/tx af independently by @bkleiner in #10396 Add feature freeze announcement by @mmosca in #10429 Fix custom OSD elements cli import by @MrD-RC in #10430 Update arming screen for better space utilisation by @MrD-RC in #10300 Allow the pilot to set the precision for altitude and distance in the OSD by @MrD-RC in #10431 Update DPS310 driver to support SPL07-003 by @DzikuVx in #10441 MSP VTX Code Updates by @geoffsim in #10355 Added IMUTemperature read function for ICM42605 by @ultrazar in #10423 Update TUNERCF405 target.h by @TUNERC-Aria in #10438 Have RSSI go from 0-100%, rather than 0-99% by @MrD-RC in #10450 Add spa06 and spl07 baro for Kakutef4/f7 FC by @jamming in #10458 Initial implementation of MSP RC stats and info messages by @MrD-RC in #10451 Revert change to MSP_SET_RAW_RC by @MrD-RC in #10461 [mspv2] pass "flags" field back to sender, define ILMI flag by @stronnag in #10464 Geozones (aka Geofence) by @Scavanger in #10459 Geozones.md by @b14ckyy in #10466 add annotated script to generate RN Changelog by @stronnag in #10468 add TBS_LUCID_H7 by @bkleiner in #10454 Add BF config to INAV target converter by @mmosca in #9556 [Fix] EZ-Tune Filter-HZ Fix by @Scavanger in #10467 Geozone RC2 Fixes by @Scavanger in #10471 Speedybee F405 AIO by @DzikuVx in #10444 gimbal_sensitivity uint8_t -> int8_t. Range is actually -16 to 15 by @mmosca in #10478 Add support for SKYSTARSSF405AIO target by @DusKing1 in #10469 Fix incorrect arming flags reporting on CLI by @mmosca in #10479 add GEPRC_TAKER_H743 target replacement by @DzikuVx in #10484 Fix nightly build by @mmosca in #10485 fixed: gps sensor can not recover from timeout in gps fix estimation mode by @RomanLut in #9574 Update osd.md for 8.0 by @MrD-RC in #10492 add target RADIOLINKF722 by @radiolinkW in #10476 Fixed wing launch mode failsafe fixes by @breadoven in #10486 BF2INAV converter updates by @mmosca in #10503 Fix PINIO in KAKUTEH7WING by @ot0tot in #10509 Show pilot name and craft name on arming screen if they are not empty by @MrD-RC in #10506 fix h7 sdcard init by @bkleiner in #10512 Omnibus F4.md: select IMU for V6 and Fireworks V2 by @sensei-hacker in #10519 h7: enable swd pins by @bkleiner in #10516 msp: expose number of vtx power levels, bands and channels by @bkleiner in #10395 Add a template for new target PR by @mmosca in #9946 f7: migrate sdcard to hal by @bkleiner in #10526 Change Autotune default max servo range by @b14ckyy in #10531 Update VTOL.md with a more detailed guide on setting up tilting servos by @dzaro-dev in #10528 Experimental bmp390 support. by @mmosca in #10542 Programming Framework.md: Fix markdown for Delta by @sensei-hacker in #10546 Correct comments on OSD symbols by @MrD-RC in #10558 Default motor stop to ON by @MrD-RC in #10568 Add support for SKYSTARSF405WING target by @DusKing1 in #10561 Add new target for HGLRCF405V2 by @HGLRC-T in #10417 SITL.md - Addtional info re joystick by @sensei-hacker in #10579 Fix barometer I2C address redefine issues by @Minderring in #10555 make gimbal trims signed int by @sensei-hacker in #10573 Simplify build and retry increasing agents by @mmosca in #10581 Fix nightly build by @mmosca in #10582 More nightly build fixes by @mmosca in #10583 Fixing nightly builds and cleaning up ci by @mmosca in #10585 Fixed wing altitude control fixes by @breadoven in #10541 Add targets for SEQUREH7 and SEQUREH7V2 by @MrD-RC in #10523 A little reminder on the OSD by @mmosca in #10589 Update description for disarm_always by @MrD-RC in #10592 Add SITL linux aarch64 build by @mmosca in #10602 O4 arming workaround by @mmosca in #10598 Fix typo by @mmosca in #10603 Strip version number of inav_SITL binaries in artifacts by @mmosca in #10604 Lower ubuntu version by @mmosca in #10605 Fix mac regular expression by @mmosca in #10609 Added extra format to Custom OSD Elements by @MrD-RC in #10594 Fix negative altitudes in OSD by @MrD-RC in #10612 Revert to actual BF font, now that DJI fixed G2 and newer by @mmosca in #10620 Remove blocking delay from batteryUpdate initialization by @mmosca in #10607 Add new target: AET-H743-Basic by @villivateur in #10600 New Contributors @pjpei made their first contribution in #10145 @Minderring made their first contribution in #10174 @jamming made their first contribution in #10175 @RobertoD91 made their first contribution in #10202 @MUSTARDTIGERFPV made their first contribution in #10222 @bartslinger made their first contribution in #10228 @KY-S0ong made their first contribution in #10279 @mbainrot made their first contribution in #9603 @trailx made their first contribution in #10335 @daijoubu made their first contribution in #10352 @bfmvsa made their first contribution in #10384 @ultrazar made their first contribution in #10423 @radiolinkW made their first contribution in #10476 @ot0tot made their first contribution in #10509 @HGLRC-T made their first contribution in #10417 @villivateur made their first contribution in #10600 Full Changelog: v20240613.18...8.0.0 Lire la source
Messages recommandés
Créer un compte ou se connecter pour commenter
Vous devez être membre afin de pouvoir déposer un commentaire
Créer un compte
Créez un compte sur notre communauté. C’est facile !
Créer un nouveau compteSe connecter
Vous avez déjà un compte ? Connectez-vous ici.
Connectez-vous maintenant