* Support DTR in serial passthrough mode to enable programming of Arduino
based devices such as MinimOSD.
Use 'serialpassthrough 5 57600 rxtx 56' and then use Ardino to program MinimOSD
Use 'serialpassthrough 5 115200' and then use MWOSD configurator to setup
* Fix comment for CDC_SetCtrlLineStateCb routine
* Handle F7 CDC interface
* Use strToPin() to allow easy port/pin specification
* Fix use of CDC_SetCtrlLineStateCb for all processor types
* Only set baud when specified
* Fix unit tests for cli
* Only register callback if needed
* Fix white space
* Provide implementation of IOConfigGPIO in SITL
* Update serialpassthrough help text
* DTR handling through serial drivers
* Fix F3, F7 and SITL builds
* If serialpassthrough command specifies baud rate of 0, set baud rate over USB. MWOSD configurator can now access config and reflash MinimOSD without rebooting and changing baud rate.
* Fix F3 build
* Fix failing unit tests
* Use resources to declare DTR pin assignment
* Don't assert DTR during normal operation as MW_OSD doesn't like it
* MW_OSD must be built with MAX_SOFTRESET defined in order to support DTR resets
* Minimise changes after dropping DTR pin param from serialpassthrough cmd
* Remove DTR pin param from serialpassthrough cmd
* Treat ioDtrTag as boolean in conditional statements
* Tidy buffer check
* Check buffer size in CDC_Itf_Control
* Fix unit test
* Add documentation for DTR
* Add note on MAX_SOFTRESET to documentation
* Remove superfluous function definitions
* Fix tabs
* Fix tabs
* Removed superfluous entried from vtable
* Backout whitespace changes unrelated to this PR
* Pass true/false to IOWrite()
* Fix line coding packing
* Add LINE_CODING structure defintion
* Revise serial documentation
* Prevent tx buffer overflow in serialPassthrough()
* Revert change unrelated to PR
* Review feedback from ledvinap
* Fix unit test
* Use PINIO to drive DTR
* Fix unit test
* Remove change unrelated to PR
* Fix SITL build
* Use shifted bits for mask definition
* Fix serialpassthrough documentation
* Only compile PINIO functionality if USE_PINIO defined
* IOConfigGPIO not needed
* Move cbCtrlLine callback to cli.c
* serialPassthrough params changed
* Check packed structure size
* Fix unit test
* Tidy up baud rate handling
* Dual-stage Gyro Filtering: PT1, FKF, and Biquad RC+FIR2
* Builds on the previous work of apocolipse.
* Fixes 'stage2'/'stage1' mis-naming to reflect where it is applied in the loop.
That is, the older Biquad, PT1, Denoise (FIR) filters are 'stage2' - applied
after dynamic and static notches (if enabled), and the controversial PT1,
'fast Kalman' filter, and Biquad RC+FIR2 filters, are 'stage1'. e.g. before
dynamic notch.
* FKF bruteforce Kalman gain removed. Calculate from half of PT1 RC constant,
automatically taking loop-time into account.
* New union type definition for stage1 filtering.
* New gyro sensor members for stage1 filter application function and states for
all three supported filter types
* New enum types for stage1 v. stage2. dterm lowpass type references 'stage2'.
* updates to CMS/MSP/FC to allow compilation (untested, probably breaks
MSP, Lua, and ~comms with BFC~).
* Refactors FKF initialization, update and associated structures to be faster by
not continuously calculating 'k'. Filter gain is calculated once during
initialization from RC constant as per PT1 and Biquad RC+FIR2. It was
discovered this converges to static value within 100 samples at 32kHz, so can
be removed. Remove related interface (CLI) settings.
* update dterm_lowpass_type to use new 'TABLE_LOWPASS2_TYPE' (biquad/pt1/FIR)
* Stage 1 defaults to PT1, 763Hz (equivalent to Q400 / R88 from quasi-kalman
filter) - suitable for 32kHz sampling modes. Can be switched to Biquad
RC+FIR2, and FKF.
* Update `#if defined(USE_GYRO_SLEW_LIMITER) to `#ifdef`.
* Includes optional Lagged Moving Average 'smoothing' pipeline step, applied (in
code) after the output of stage1.
* (diehertz): Removed redundant pointers from gyro filtering
* blackbox: fix indentation
* cms IMU menu: fix indentation
* filters: remove USE_GYRO_FIR_FILTER_DENOISE in filter type enum
* gyro sensors: go back to `if defined()` form. for slew limiter
* gyro sensors: increment parameter group version
* due to non-appending changes, the version must be bumped.
* Move ADC to DMA2_Stream0 to avoid conflict
Motor 6 output is declared to use DMA2_ST4, which is used by default by ADC so Dshot is not possible on that output.
* Omitting channel defines
ADC channels are inferred from corresponding pins.
* If RSSI Channel is set to Disabled when using S.Bus then generate RSSI signal using frame drop flags from the rx
* Set RSSI max level for S.Bus to 1024 so OSD defaults can be used
* Failsfafe must be detected rather than just reporting dropped frames
* Failsafe implies dropped frames
* Remove failsafe debug
* Use RSSI_SOURCE_RX_PROTOCOL
* Add rssi_from_rx_protocol to enable siqnal quality from rx to be processed as RSSI
* Use RSSI_MAX_VALUE definition
* Use rssi_from_rx_protocol flag for fport rx
* Update serialpassthrough help text
* Revert erroneous commit
* Use rssi_src_frame_errors boolean
* rssi_src_frame_errors = ON | OFF
* Moved rssi_src_frame_errors to end of rxConfig_t struct
* Add documentation of rssi_src_frame_errors
* Synthesise RX_FRAME_FAILSAFE flag to protect from bad implementation in receivers
* Match rx failsafe behaviour exactly
* Only set RX_FRAME_COMPLETE if valid frame is received
* RSSI_SOURCE_FRAME_ERRORS moved to end of rssiSource_e enum
* Removed superfluous else if clause
* Restore debug code
* Restore stateFlags
* Set RX_FRAME_DROPPED flag when failsafe is triggered
* Second PT1 on DTerm
This PR replaces the default biquad filter with a second PT1 set to
200Hz.
Basically allows the user to enable a second, set point configurable,
PT1 type first order low-pass filter on DTerm.
This is useful because most noise in most logs arises from D, not P.
The default is set to on, at twice the normal Dterm setpoint. This
provides greater Dterm cut than a single PT1, and twice the steepness
of cut above the second setpoint. Modelling shows significant
reductions in higher frequency Dterm noise with only minor additional
delay.
The improvement in noise performance will be less than for biquad, but
the delay is considerably less.
If with the default settings the overall noise improves a lot, it may
be possible bring D both filtering set points to higher numbers (e.g.
140/280), or alternatively remove other filters such as the notch
filters, while maintaining an adequate level of control over noise.
* Update names, old defaults, fix whitespace
Defaults restored to biquad with second PT1 off. ‘lpf’ retained as
abbreviation for values, otherwise generally remove ‘Filter’ where
redundant, replace ‘FilterLpf’ with ‘Lowpass’, etc, thanks Fujin and
DieHertz
* Remove underscore in lowpass_2, add hz to setpoint for lowpass
Thanks DieHertz
* completed replacing lpf with lowpass, added _hz to all lowpass set points in profile
Thanks DieHertz
* fix whitespace
fixed whitespace in settings.c
* whitespace attempt #57
* change lpf to lowpass where appropriate elsewhere
Note did not change OSD abbreviations, they are still LPF, and did not
change gyro_lpf anywhere.
* second attempt at a simple PT1 implementation
Basically copied from the DtermNotch implementation
* Second PT1 on DTerm
This PR replaces the default biquad filter with a second PT1 set to
200Hz.
Basically allows the user to enable a second, set point configurable,
PT1 type first order low-pass filter on DTerm.
This is useful because most noise in most logs arises from D, not P.
The default is set to on, at twice the normal Dterm setpoint. This
provides greater Dterm cut than a single PT1, and twice the steepness
of cut above the second setpoint. Modelling shows significant
reductions in higher frequency Dterm noise with only minor additional
delay.
The improvement in noise performance will be less than for biquad, but
the delay is considerably less.
If with the default settings the overall noise improves a lot, it may
be possible bring D both filtering set points to higher numbers (e.g.
140/280), or alternatively remove other filters such as the notch
filters, while maintaining an adequate level of control over noise.
* Rebase
* Remove underscore in lowpass_2, add hz to setpoint for lowpass
Thanks DieHertz
* completed replacing lpf with lowpass, added _hz to all lowpass set points in profile
Thanks DieHertz
* fix whitespace
fixed whitespace in settings.c
* whitespace attempt #57
* change lpf to lowpass where appropriate elsewhere
Note did not change OSD abbreviations, they are still LPF, and did not
change gyro_lpf anywhere.
* second attempt at a simple PT1 implementation
Basically copied from the DtermNotch implementation
* Whitespace fix - thanks, Ledvinap
* Fix PG issue
by moving added dterm_lowpass2_hz to bottom of struct
* Got rid of redundant indirection
* Fixed indentantion shifts
Previously the OSD stats would always display even if the OSD disable switch mode was active.
Additionally, since the OSD stats page must now be dynamically refreshed rather than only rendered once at disarm, "live" stats like RTC clock and the timer "ON TIME" continue to update and display current information. All other stats related to the previous flight remain static as of the disarming.
* * FAST_RAM-ing variables used to compute FFT
* Eradicated global static variables in favour of define
* FFT_WINDOW_SIZE / 2 replaced with FFT_BIN_COUNT
* Limit call count of filters update to necessary minimum on 32k and 16k gyro sampling rate
* Dynamic filter recalculation freq. is at least FFT_SAMPLING_RATE + update time
* Moved global variables used in local scope only to local scope
* * Based on diehertzs review I removed all 0 initializations of global variables
* * Fixed calculation of update frequency for center frequency filter, thx rav-rav for pointing the problem
* * Silenced the warning signed vs unsigned comparison
* * Replaced magick values 3*4 and 12 with preprocessor macro as requested by DieHertz
* * Replaced hardcoded axis count with proper preprocessor macro
After disarming and allowing the gyros to settle with no motion, temporarily increase the dcmKpGain to rapidly converge on the correct attitude as indicated by the accelerometer (if present).
Addresses the case of the attitude estimate becoming significantly incorrect after a crash due to high gyro rates. While the estimate will eventually converge, it does so quite slowly. The pilot may re-arm before the estimate has corrected leading to instant flips in self-leveling modes. By speeding up the convergence when disarmed we help reduce this risk.
The function imuIsAccelerometerHealthy() was only using the last ACC sample to determine if the sensor was returning "healthy" data. This then controlled whether the IMU attitude calculation considered ACC data at all. There were two problems with this:
1. A single sample from the ACC can be very noisy and exceed the check threshold resulting in a false negative on the health of the sensor.
2. The attitude calculations exclusively used the averaged ACC samples so there was an inconsistency in checking only the last sample to determine if the data was useful.
This change should lead to fewer occurences of the ACC sensor data being ignored in the attitude estimation which should in turn improve the overall estimate.
and OSD_WARNINGS is visible in the OSD.
The stats screen was preventing the user from knowing that a disarm might be casued by runaway takeoff. If the warnings element is visible it will have the message "RUNAWAY" but the disarm it triggers caused the stats display to replace the screen.
The change prevents the stats page from displaying if the ARMING_DISABLED_RUNAWAY_TAKEOFF flag is set and the OSD_WARNINGS element is visible. Otherwise the stats screen is displayed as normal.
Changed the logic so that if currently armed and the previous arming state was disarmed, then blank out the message for just this single iteration. This should allow any elements behind to be properly displayed when armed.
* CF/BF - Update DSP_Lib and STM32F7/Drivers/CMSIS to CMSIS 5.3.0.
CMSIS 5.3.0 - https://github.com/ARM-software/CMSIS_5/releases/tag/5.3.0
* cleanup lib.
* pfft
* relocate driver files from lib/main/CMSIS/CM* to lib/main/STM32xx
folders
* Move DSP folder inside CM5.
It came from the same source as the other files inside CM5
* Remove the CM5 folder and move the files in it one level up.
* Fix for minthrottle when feature 3d and pwm enabled
* add parameters for min and max 3d output
* bug fix
* remove new parameters from msp
* remove new parameters again
* fixed indentation
If USE_MAG was undefined but USE_GPS was defined, then the "else if" would incorrectly apply to a condition above making the USE_GPS section unlikely to execute.
* Add ledstrip_grb_rgb setting (GRB or RGB) to handle WS2811 or WS2812 LED drivers
* Rename setting lookup table to lookupLedStripPackingOrder
* Fix call to ws2811UpdateStrip
* Fix unit test
* Use ledStripFormatRGB_e enumeration for RGB packing format
* Fix unit test
* Whoops. Make ledStripFormatRGB_e match lookupLedStripFormatRGB
* Applied review feedback
* Add documentation of ledstrip_grb_rgb