WaF Bot Posté(e) Février 9, 2023 Signaler Partager Posté(e) Février 9, 2023 Hello and welcome to INAV 6 "Horizon Hawk" 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 Discord Server INAV Official on Facebook Tested and suggested hardware can be found here Important Notes The STM32 F3 code was removed from repository, it's no longer possible to compile F3 locally Upgrading from a previous release Upgrading from INAV 5 and 5.1 Download and install the new configurator Save to a file the current diff all from the CLI. Upgrade to INAV 6 using the Full Erase option in the configurator. 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 a large number of 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 6.0 features, and enjoy! Upgrading from older versions Please follow the instructions on this page. Important changes New AHRS (Attitude & Heading Reference System) INAV 6.0 includes a complete rework of the AHRS for Attitude Estimation, to make sure INAV always knows its correct attitude relative to the ground. This should once and for all fix the issue, known as "Horizon Drift" and makes any navigation mode as well as self-levelling modes like ANGLE fully reliable and allows much more precise GPS-Navigation. This affects Fixed Wing as well as Multirotor. The best results are given if the craft is equipped with GPS and in the case of Multirotor also with a compass. But also for pure LOS Craft that have no GPS on board, the AHI stability is noticeably improved in most situations. To work best with non-GPS Fixed Wings, the Reference Airspeed has to be set according the average cruise speed of the craft. For Fixed Wing Craft with no GPS: set fw_reference_airspeed = (set this in cm/s. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present.) HUD Offset change The operation of osd_horizon_offset has been reversed, to make it more intuitive. If you have a non-zero value for osd_horizon_offset it will need to be inverted. For example, osd_horizon_offset = 1 would become osd_horizon_offset = -1. Positive values move the HUD up, and negative values move it down. RTH Trackback When triggered the craft returns along the trackback route until the end is reached at which point it reverts to normal RTH heading directly home. It doesn't perform the RTH climb phase but instead uses the track point altitude but with altitude never allowed below the altitude of the start point so it can climb but never descend below the start point. OFF by default, adjust nav_rth_trackback_mode to enable. For details see #7988 Accelerometer calibration is optional Accelerometer calibration is required only if any of the Accelerometer Based Flight Modes or Failsafe procedures is configured. For example, ACC calibration will be needed when Failsafe RTH is enabled, or any GPS assisted flight modes is configured. Acro only multirotor and fixed wings do not require calibration. nav_extra_arming_safety OFF option The off option has been removed from nav_extra_arming_safety. Instead, the allow_bypass can be used for with the same effect. To allow the bypass, yaw right and arm. The extra arming safety features will be disabled until the next power cycle of the battery. Please update your diff if you use this parameter; either manually, or using this tool. Improved fixed wing waypoint course tracking Attempts to improve fixed wing WP course tracking accuracy by adding a couple of options: Tracking accuracy option that forces craft toward the waypoint course line as quickly as possible and actively tracks the line thereafter. A single setting adjusts the strength of the tracking behaviour. Works for WP mode and RTH trackback. Option is disabled by default. Turn smoothing option for waypoint turns. Sets a loiter point within the turn such that the craft follows a loiter turn path that either passes through the waypoint or cuts the turn missing the waypoint (2 settings possible). Only works for WP mode. Option is disabled by default. See #8234 for details Support for Hardware In The Loop simulator in X-Plane 11 INAV flight controller can be used with X-Plane 11 flight simulator. Very useful for training, testing and debugging. Requires X-Plane 11 and HITL Plugin https://github.com/RomanLut/INAV-X-Plane-HITL Waypoint multi-mission in flight mission change Allows WP multi-missions to be changed in flight using new mission change mode. With mode active the required mission index can be selected by cycling through missions using the WP mode switch. Selected mission is loaded when mission change mode is switched off. Mission index can also be changed through addition of a new Mission Index adjustment function which should be useful for DJI users unable to use the normal OSD mission related fields. See #8354 for details MSP Displayport fixes and updates INAV has now support for various flavours of the MSP Displayport protocol used by HDZero, DJI Goggles 2, Walksnail Avatar or WTFOS. Based on the osd_video_system setting different canvas sizes and glyphs are used. Available options are: AUTO - for analog systems only PAL NTSC HDZERO DJIWTF AVATAR BF43COMPAT - keep the compatibility with Betaflight 4.3 implementation by lowering canvas size, lowering the number of OSD glyphs and matching to Betaflight character mapping. Required for DJI MSP Displayport with DJI O3 Air Unit Enhance programming options for waypoint missions The programming framework surrounding waypoints has changed. This has caused a conflict in compatibility with previous versions of INAV. If you use anything in the programming tab. Please run your diff through this conversion tool, to keep your logic conditions working. Please feel free to check out the new waypoint related logical switch operands in the Programming Framework document. Increase nav_wp_safe_distance maximum nav_wp_safe_distance has been replaced with nav_wp_max_safe_distance. This setting uses metres, and used to define the maximum distance away that the first waypoint can be. Please update your diff if you use this parameter; either manually, or using this tool. Stop allowing navigation modes to be active while arming The ability to arm the craft while in a navigation mode has been removed. The only people who this will effect are those who use permanently enabled autolaunch. Pre-6.0 you could arm while in a navigation mode. However this is dangerous, as it is easy to not realise, arm, disable the launch, then have the motor go to the cruise throttle. You will still be able to use a navigation mode as the exit mode from a launch. You just need to use the correct procedure for initiating the launch: Be in a non-navigation mode Arm Select the flight mode that you want to use on launch exit Raise the throttle to the level you want on launch exit The motor will enter idle if idle throttle is used, or await being thrown Throw the plane in to the air, and autolaunch will trigger Disarm on land by default The disarm on landing flag is now set to ON by default. This means, after successful automated landing your aircraft should disarm and stop the motors automatically! Automated landing manual activation Allows an emergency landing to be triggered manually as required. Landing started or ended by rapid toggling of PosHold mode, at least 5 times at a minimum rate of 1Hz. Emergency landing position hold added which will work for all emergency landings regardless of cause so long as a valid position is available. Failsafe inhibited during manual emergency landing to allow landing to continue if Failsafe triggered whilst active. Other changes Gyro noise peaks are now logged into blackbox as separate fields, not debug options. Setting documentation Raw gyro signal is now logged into blackbox as separate field, not debug options. Setting documentation Adds auto smoothing of RC input based on RX refresh rate. Disabled by default, can be enabled with SET rc_filter_auto=ON Wind Estimator is now giving proper results 3D Matrix filter improves PID tuning on noisy Multirotors. See #8253 Strobe lights support. See #8536 Kakute H7 V2 Invert PINIO2 so VTX is ON by default See #8628 Other removed functions MTK GPS protocol support NAZA GPS protocol support BNO055 Secondary IMU function MPU6050 gyro support SPI RX protocol support JR XBUS RX protocol support SUMH RX protocol support New targets Foxeer F722 V4 Foxeer F745 AIO V3 Kakute H7 V2 SpeedyBee F745 AIO Zeez F7 V3 Diatone Mamba F722 WING AocodaRC F4 V2 HakRC F722D HakRC F411 AIO HakRC F405 DJI CLI Changed settings Note: nav_extra_arming_safety The OFF option has been removed. ON and ALLOW_BYPASS are now the only valid options. ALLOW_BYPASS permits arming in "navigation unsafe" condition by temporally applying full right yaw when operating the arm switch. Name Values acc_hardware Removed: MPU6050 debug_modes New: POS_EST debug_modes Removed: GYRO, SBUS, FPORT, ERPM, RPM_FILTER, RPM_FREQ, DYNAMIC_FILTER, DYNAMIC_FILTER_FREQUENCY, IRLOCK, KALMAN_GAIN, PID_MEASUREMENT, SPM_CELLS, SPM_VS600, SPM_VARIO, IMU2, SMITH_PREDICTOR gps_provider Removed: UNUSED, NAZA, MTK mag_hardware Removed: GPSMAG nav_extra_arming_safety Removed: OFF osd_video_system New: HDZERO, DJIWTF, AVATAR, BF43COMPAT osd_video_system Removed: HD receiver_type Removed: SPI serial_rx Removed: SUMH, XB-B, XB-B-RJ01 New Items Name Description ahrs_acc_ignore_rate Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy Values: 0 - 30 Default: 15 ahrs_acc_ignore_slope Half-width of the interval to gradually reduce accelerometer weight. Centered at imu_acc_ignore_rate (exactly 50% weight) Values: 0 - 10 Default: 5 ahrs_dcm_ki Inertial Measurement Unit KI Gain for accelerometer measurements Values: 0 - 65535 Default: 50 ahrs_dcm_ki_mag Inertial Measurement Unit KI Gain for compass measurements Values: 0 - 65535 Default: 50 ahrs_dcm_kp Inertial Measurement Unit KP Gain for accelerometer measurements Values: 0 - 65535 Default: 2000 ahrs_dcm_kp_mag Inertial Measurement Unit KP Gain for compass measurements Values: 0 - 65535 Default: 2000 ahrs_gps_yaw_windcomp Wind compensation in heading estimation from gps groundcourse(fixed wing only) Default: TRUE ahrs_inertia_comp_method Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop Default: VELNED dynamic_gyro_notch_3d_q Q factor for 3D dynamic notches Values: 1 - 1000 Default: 200 dynamic_gyro_notch_mode Gyro dynamic notch type Default: 2D failsafe_mission_delay Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end. Values: -1 - 600 Default: 0 nav_auto_disarm_delay Delay before craft disarms when nav_disarm_on_landing is set (ms) Values: 100 - 10000 Default: 1000 nav_fw_launch_manual_throttle Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised). Default: FALSE nav_fw_wp_tracking_accuracy Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable. Values: 0 - 10 Default: 0 nav_fw_wp_tracking_max_angle Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved. Values: 30 - 80 Default: 60 nav_fw_wp_turn_smoothing Smooths turns during WP missions by switching to a loiter turn at waypoints. When set to ON the craft will reach the waypoint during the turn. When set to ON-CUT the craft will turn inside the waypoint without actually reaching it (cuts the corner). Default: OFF nav_land_detect_sensitivity Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases. Values: 1 - 15 Default: 5 nav_rth_trackback_distance Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m]. Values: 50 - 2000 Default: 500 nav_rth_trackback_mode Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only. Default: OFF nav_wp_max_safe_distance First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check. Values: 0 - 1500 Default: 100 osd_ahi_pitch_interval Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD) Values: 0 - 30 Default: 0 osd_msp_displayport_fullframe_interval Full Frame redraw interval for MSP DisplayPort [deciseconds]. This is how often a full frame update is sent to the DisplayPort, to cut down on OSD artifacting. The default value should be fine for most pilots. Though long range pilots may benefit from increasing the refresh time, especially near the edge of range. -1 = disabled (legacy mode) , 0 = every frame (not recommended) , default = 10 (1 second) Values: -1 - 600 Default: 10 osd_pan_servo_indicator_show_degrees Show the degress of offset from centre on the pan servo OSD display element. Default: FALSE osd_pan_servo_offcentre_warning Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. 0 means the warning is disabled. Values: 0 - 45 Default: 10 pilot_name Pilot name Default: rc_filter_auto When enabled, INAV will set RC filtering based on refresh rate and smoothing factor. Default: FALSE rc_filter_lpf_hz RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values Values: 15 - 250 Default: 50 rc_filter_smoothing_factor The RC filter smoothing factor. The higher the value, the more smoothing but also the more delay in response. Value 1 sets the filter at half the refresh rate. Value 100 sets the filter to aprox. 10% of the RC refresh rate Values: 1 - 100 Default: 30 Removed Items Name Description baro_median_filter eleres_freq eleres_loc_delay eleres_loc_en eleres_loc_power eleres_signature eleres_telemetry_en eleres_telemetry_power failsafe_mission see new failsafe_mission_delay imu2_align_pitch imu2_align_roll imu2_align_yaw imu2_gain_acc_x imu2_gain_acc_y imu2_gain_acc_z imu2_gain_mag_x imu2_gain_mag_y imu2_gain_mag_z imu2_hardware imu2_radius_acc imu2_radius_mag imu2_use_for_osd_ahi imu2_use_for_osd_heading imu2_use_for_stabilized imu_acc_ignore_rate see new ahrs_* equivalent imu_acc_ignore_slope see new ahrs_* equivalent imu_dcm_ki see new ahrs_* equivalent imu_dcm_ki_mag see new ahrs_* equivalent imu_dcm_kp see new ahrs_* equivalent imu_dcm_kp_mag see new ahrs_* equivalent nav_fw_auto_disarm_delay See generic nav_auto_disarm_delay nav_mc_auto_disarm_delay See generic nav_auto_disarm_delay nav_wp_safe_distance see nav_wp_max_safe_distance rc_filter_frequency rx_spi_id rx_spi_protocol rx_spi_rf_channel_count Changelist The full list of changes is available here The full list of INAV Configurator changes is available here What's Changed from INAV 6 RC1 Add a mapping for 3D kph and mph symbols by @DzikuVx in #8761 Pan Enhancements and cardinal markers for ESP32 Radar by @MrD-RC in #8699 Fix WS2812 led definition in IFLIGHT_BLITZ_F722 target by @mmosca in #8770 ahrs parameter names change by @shota3527 in #8767 Fix formatting of decimal numbers in BF43COMPAT display mode by @mmosca in #8776 Simplify and fix altitude processing for BF43COMPAT by @DzikuVx in #8779 What's Changed from INAV 5.1 Clean old box comments by @JulioCesarMatias in #8076 Update Omnibus F4.md by @gigabytebit in #8088 Remove the rest of the PCA9685 driver by @JulioCesarMatias in #8085 Fix mixing motor and servo on same timer. by @sasodoma in #8071 [fc/fc_msp_box.c] Remove uncompiled line by @JulioCesarMatias in #8077 Clear the #if 0 by @JulioCesarMatias in #8118 Target release cleanup by @DzikuVx in #8108 Make use of calc_length_pythagorean_2D on some lines by @JulioCesarMatias in #8101 Edit GPS Provider list by @JulioCesarMatias in #8102 [flash_m25p16.c] Add W25Q128 variant by @JulioCesarMatias in #8054 Drop MTK GPS by @JulioCesarMatias in #8084 RTH Trackback by @breadoven in #7988 Remove nav_extra_arming_safety = OFF option by @MrD-RC in #8106 Fix PC2/PC3 ADC not working on MAMBAH743 by @hogthrob in #8149 [BMP280] Allow target-specific I2C address definition by @RomanLut in #8129 Drop support for NAZA GPS by @DzikuVx in #8144 Release 5.0.0 by @DzikuVx in #8061 Fix wrong merge by @DzikuVx in #8151 INAV 6 version bump by @DzikuVx in #8141 Set Gyro Raw as an independent Blackbox field, not debug mode by @DzikuVx in #8139 [cli.c] RC map code aesthetics by @JulioCesarMatias in #8153 Remove F3 from the codebase by @DzikuVx in #8053 Settings.md: Document osd_ahi_reverse_roll by @sensei-hacker in #8167 Drop a function used only in STM32F3 by @JulioCesarMatias in #8164 Drop the BNO055 I2C version by @DzikuVx in #8168 Drop the JR XBUS support as not used by @DzikuVx in #8176 Remove an unused definition by @JulioCesarMatias in #8181 Reorder box_t to save few hundreds of bytes by @JulioCesarMatias in #8180 Drop SPI RX as not used by any supported hardware by @DzikuVx in #8173 Reset fixed wing heading status on disarm by @breadoven in #8160 OmnibusF4 RX serial fix by @breadoven in #8175 Increased FW launch abort pitch/roll stick dead band by @breadoven in #8161 Remove additional validation for motor rate by @DzikuVx in #8174 Fix surface mode msp box availability logic by @breadoven in #8171 Update VTx.md by @MrD-RC in #8187 Opimise navwaypoint_t stuct alignment by @stronnag in #8182 Optimize memory for better alignment by @DzikuVx in #8183 Fix RX Serial Enumeration by @JulioCesarMatias in #8191 Remove unused rxRefreshRate by @JulioCesarMatias in #8189 Configurator: Reset PIDs button to use applied defaults by @MrD-RC in #8185 Log gyro noise peaks as separate fields by @DzikuVx in #8197 Drop SUMH RX protocol by @DzikuVx in #8198 Update jetiexbus.c by @RoadyFPV in #8202 Support for Flash Memory W25N01G of 128MB by @JulioCesarMatias in #8166 [STM32F3] Remove everything else by @JulioCesarMatias in #8204 Debug cleanup by @DzikuVx in #8211 [Building in Linux.md] Fix Typo by @JulioCesarMatias in #8222 Remove unused header file by @JulioCesarMatias in #8221 Drop the MPU-6050 Support by @JulioCesarMatias in #8213 Remove barometer median filter by @digitalentity in #8201 OSD PG reset template version bump by @breadoven in #8217 Nav launch stick abort deadband setting by @breadoven in #8218 RC interpolation updates by @DzikuVx in #8212 [config_eeprom.c] Replace a function with another one that already exists in the library by @JulioCesarMatias in #8215 Report motor RPM via MSP by @DzikuVx in #8225 Make HUD offset more intuitive by @MrD-RC in #8226 Nav launch manual throttle option by @breadoven in #8134 Remove some NO optimizations made by MCU_FLASH_SIZE by @JulioCesarMatias in #8230 fixed wind estimator by @RomanLut in #8228 fixed wind direction icon on osd by @RomanLut in #8227 Update Building in Windows 10 or 11 with MSYS2.md by @pwnept in #8248 Update Matrix Filter to 3D Matrix Filter by @DzikuVx in #8253 Add glide time, glide distance, and climb efficiency OSD elements by @MrD-RC in #8081 Update PPM by @MrD-RC in #8269 Updated profiles.md doc by @MrD-RC in #8279 Add USER3 mode by @shellixyz in #8276 Add target: NEUTRONRCH7BT by @shellixyz in #8277 Enforce waypoint altitude tolerance fix by @breadoven in #8280 Improved fixed wing waypoint course tracking by @breadoven in #8234 Allow autolevel in nav_course_hold_mode by @FinalFrag in #8178 Fix altitude conversion in MSP_SET_RAW_GPS by @stronnag in #8337 Updated CMS GPSNAV PIDs by @breadoven in #8326 make use of the MS2S macro whenever possible by @JulioCesarMatias in #8332 Support for Hardware In The Loop simulator in X-Plane 11 by @RomanLut in #8268 fixed BOX_PERMANENT_ID_USER3 collision by @RomanLut in #8346 Use ARRAYLEN macro where applicable by @JulioCesarMatias in #8323 Fix uint8_t to bool by @JulioCesarMatias in #8325 Rename pitotCalculateAirSpeed() by @JulioCesarMatias in #8330 INAV 5.1.0 Release branch by @DzikuVx in #8186 Mamba 2022B targets by @DzikuVx in #8368 Fix S1 by removing LED conflict by @DzikuVx in #8371 [OMNIBUSF4V3] Add BMI270 support by @JulioCesarMatias in #8351 [fc_core.c] Rename annexCode void by @JulioCesarMatias in #8329 Drop the old HIL by @JulioCesarMatias in #8281 Missing Nav default settings fix by @breadoven in #8396 Treat wp.p3 as bitfield by @stronnag in #8393 HakRC F405 DJI target by @nmaggioni in #8384 HakRC F722D target by @nmaggioni in #8387 Re-order boxmodes to have as little disruption to 5.1 as possible by @MrD-RC in #8394 added scripts to update Settings.md with Docker by @RomanLut in #8350 HakRC F411 AIO target by @nmaggioni in #8385 WP mode failsafe delay setting by @breadoven in #8363 Nav landing fixes by @breadoven in #8358 Waypoint multi-mission in flight mission change by @breadoven in #8354 Make sure first motorCount outputs get assigned to motor on MR by @mluessi in #8289 make use of the US2S macro whenever possible by @JulioCesarMatias in #8331 [INS] Use Acc and Gyro calibration validation to calibrate the 1G of the acceleration by @JulioCesarMatias in #8214 [HITL Mode] Make a "makeup" in the algorithm by @JulioCesarMatias in #8356 Enable LEDs by default on JBF7PRO by @nmaggioni in #8412 iNav to INAV by @DzikuVx in #8410 set GPS timeout to 2000ms by @stronnag in #8423 Add landing sensitivity setting + duplicate setting fix by @breadoven in #8427 fix "Blackbox Internals" encoding and update by @stronnag in #8431 MSP Displayport by @DzikuVx in #8435 Mamba f722 wing target by @DzikuVx in #8436 Add macro data conversion to MPU by @JulioCesarMatias in #8432 enable virtual pitot on F411 and F722 by @shota3527 in #8428 mavlink telemetry half/full duplex support by @RomanLut in #8274 Throw out all the setup part of the Gyro interrupt routine by @JulioCesarMatias in #8199 Allow more applied_defaults by @DzikuVx in #8437 Disable stick commands if in CLI by @MrD-RC in #8406 Fix bool values by @JulioCesarMatias in #8445 Pass the variable from uint8_t to bool by @JulioCesarMatias in #8444 ZEEZF7V3 target by @nmaggioni in #8442 Add ZeroFArray Macro and make use of it in some parts by @JulioCesarMatias in #8447 Rename the LOG function macros by @JulioCesarMatias in #8446 Stop showing all LCs for every LC set in dump by @MrD-RC in #8448 inav->INAV... redo by @DzikuVx in #8468 Add 2nd PINIO to MATEKF405SE for better use of resources by @MrD-RC in #8438 Add target KAKUTEF4V23. Support for M5 and M6 outputs. by @marianomd in #8135 Update virtual pitot to use 3d speed by @shota3527 in #8458 AHRS centrifugal force compensation by @shota3527 in #8403 Added support for DJI wtfos MSP-OSD full screen 60x22 OSD by @jeffhendrix in #8434 New SpeedyBee targets by @DzikuVx in #8478 Update Github actions version by @JulioCesarMatias in #8481 [Displayport MSP] Add Macros by @JulioCesarMatias in #8480 Update PixRacer README.md by @JulioCesarMatias in #8486 Fix read of DPS310 coef C11 by @JulioCesarMatias in #8485 Fix MPU6000 for HAKRCKD722 by @nmaggioni in #8493 Fix MPU6000 for HAKRCF405D by @nmaggioni in #8492 Drop IMU2 functionality by @DzikuVx in #8491 fix lpf config for bmi270/bmi160 by @shota3527 in #8495 add target aocodarcf4v2 by @dlt2018 in #8416 Add support HDZero 30x16 mode by @geoffsim in #8476 Drop some PPM definitions by @JulioCesarMatias in #8515 Update gyro orientation for Mamaba H743_2022B by @DzikuVx in #8505 Kakute H7 V2 by @DzikuVx in #8522 [target] Clear some unused defitions by @JulioCesarMatias in #8517 Added link to "something disabled" wiki by @MrD-RC in #8524 Fix heading graph on PixelOSD by @MrD-RC in #8526 [scheduler.c] Remove duplication by @JulioCesarMatias in #8556 RTH Trackback - suspend track recording on fixed wing during Loiter by @breadoven in #8512 Add PINIO 3 & 4 plus MATEKF722PX_PINIO target by @MrD-RC in #8401 Update ci.yml by @MrD-RC in #8560 Foxeer F722 V4 by @DzikuVx in #8544 Update Battery.md by @MrD-RC in #8559 [ci] remove remaining instances of ubuntu-18.04 by @stronnag in #8562 Waypoint turn smoothing and tracking accuracy improvements by @breadoven in #8519 OSD AHI pitch interval redraw option by @breadoven in #7018 Correct Omnibus readme by @sensei-hacker in #8573 Use course over ground as the default for fixed wing navigation "heading" by @breadoven in #8529 Changed CleanFlight to INAV by @MrD-RC in #8583 Fix incorrect temperature shown on OSD by @JulioCesarMatias in #8539 Remove unnecessary parameters from profiles by @MrD-RC in #8451 Increase nav_wp_safe_distance maximum by @MrD-RC in #8589 Add EDGE, DELAY, DELTA, APPROX_EQUAL switches and TIMER to Logic Conditions by @MrD-RC in #8581 Add symbols for remaining time/distance by @MrD-RC in #8584 Update target AOCODARCF7DUAL and remove MPU6500 by @dlt2018 in #8510 New debug_mode POS_EST that is useful for autonomous flight by @ricardodeazambuja in #8549 Foxeer F745AIO V3 by @DzikuVx in #8543 Change logo size for future enhancements by @MrD-RC in #8585 Fixed wing Nav altitude control fix by @breadoven in #8590 OSD Ground Course and Cross Track Error by @breadoven in #8604 Throttle low clean up by @breadoven in #8601 Waypoint accuracy tweak by @breadoven in #8620 Update target.h for AtomRC F405 NAVI by @DzikuVx in #8610 Stop allowing navigation modes to be active while arming. by @MrD-RC in #8611 Kakute H7 V2 Invert PINIO2 so VTX is ON by default by @DzikuVx in #8628 Add a BF4.3 Compatible restricted OSD implementation. by @mmosca in #8631 Update Navigation.md by @b14ckyy in #8633 Increase number of voltage digits in BF compatibility mode OSD by @mmosca in #8634 Be consistent in using #ifdef USE_SAFE_HOME by @sensei-hacker in #8635 [CLI] add missing arming flag name by @stronnag in #8637 Fix X8 mode on FoxeerF722V4 by @DzikuVx in #8644 fixed crsf attitude yaw overflow by @RomanLut in #8638 changed WP mode priority in crsf telemetry by @RomanLut in #8639 Nav "Yaw" usage refactor by @breadoven in #8643 Fix git security issue with docker build by @skeet70 in #8558 Add more symbols to BF43 translation table. by @mmosca in #8641 Consolidate post flight and non-essential save calls in to a single save action by @MrD-RC in #8439 add new target 'AOCODARCF722MINI' by @dlt2018 in #8472 [doc] document changes introduced by #8446 by @stronnag in #8660 Fixed wing climb rate fool proofing fix by @breadoven in #8661 OSD Heading field fix + field display index update by @breadoven in #8624 Emergency arming simplification by @breadoven in #8659 use MAX_SUPPORTED_RC_CHANNEL_COUNT instead of hardcoded 16 by @RomanLut in #8676 Add version info to cliStatus by @OptimusTi in #8671 Fix Docker build UID/GID mapping by @nmaggioni in #8679 Unused Baro filter fix by @breadoven in #8688 DEBUG_ALTITUDE fix by @breadoven in #8693 RTH Trackback fix by @breadoven in #8697 Rename functions to avoid confusion why it does not write eeprom by @sakisdog in #8690 Updates to CLI Outputs by @MrD-RC in #8689 send value throttle in telemetry exactly as shown on osd by @RomanLut in #8652 Update RUSH_BLADE_F7 and add RUSH_BLADE_F7_HD targets by @nmaggioni in #8680 Enhance programming options for waypoint missions by @MrD-RC in #8579 Update MSPDisplayPort and add Walksnail Avatar settings by @MrD-RC in #8654 Update Building in Windows with MSYS2.md by @pwnept in #8702 Change tz_offset min and max by @MrD-RC in #8470 Use BF SYM_AH_BAR9_4 as replacement for INAV SYM_AH_V_START family in BF Compatibility OSD mode by @mmosca in #8709 FW Nav Course Hold control method change by @breadoven in #8586 Disarm on land by default by @DzikuVx in #8711 Updates in the display of wind estimator by @shota3527 in #8523 Disable mAh scaling for BF compatibility by @DzikuVx in #8717 Add RPM symbol translation by @DzikuVx in #8718 Switch H7 to -Ofast optimizations by @DzikuVx in #8719 Add strobe overlay to RGB LEDs by @mmosca in #8536 Add pilot name by @MrD-RC in #8720 Fixed wing OSD home heading arrow and error fix by @breadoven in #8723 Fix MATEK F405SE and F722PX targets with PINIO by @MrD-RC in #8728 Fix build error in osd.c when USE_MSP_DISPLAYPORT is not defined. by @mmosca in #8729 [Doc] update blackbox.md for 6.0 cli options by @stronnag in #8732 Landing detector improvements by @breadoven in #8737 Manual emergency landing FW and MR by @breadoven in #8686 Correct INAv to INAV by @pwnept in #8746 add icm42688p support in MATEKF411TE target by @MATEKSYS in #8748 Landing detection invalid velocity protection by @breadoven in #8743 Update Flight Mode operand in programming framework by @MrD-RC in #8747 New Contributors @gigabytebit made their first contribution in #8088 @sasodoma made their first contribution in #8071 @hogthrob made their first contribution in #8149 @RoadyFPV made their first contribution in #8202 @pwnept made their first contribution in #8248 @FinalFrag made their first contribution in #8178 @shota3527 made their first contribution in #8428 @marianomd made their first contribution in #8135 @ricardodeazambuja made their first contribution in #8549 @mmosca made their first contribution in #8631 @b14ckyy made their first contribution in #8633 @skeet70 made their first contribution in #8558 @sakisdog made their first contribution in #8690 Full Changelog: 5.1.0...6.0.0-RC1 Full Changelog: 5.10...6.0.0-RC2 Lire la source Lien vers le commentaire Partager sur d’autres sites More sharing options...
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