* add icm40609d
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
refactor include
* add support for setting filters from config
* set optimal settings for AAF
* add settings DEC2 M2 filter for Gyro
* set 3Rd hardware UI filters for Gyro&Accel
* update comments filter order
* set readFN for read SPI data via DMA, add INT1 to pulse mode, push-pull, active high
* fix PR issue
* revert INT1 POLARITY to ACTIVE HIGH
* refactor icm40609GetAafParams
* Update src/main/drivers/accgyro/accgyro_spi_icm40609.c
Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com>
* Update src/main/drivers/accgyro/accgyro_spi_icm40609.c
* update link to datasheet
* fix typo
Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com>
* hover point throttle curve adjustment
* Update src/main/fc/rc.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/fc/rc.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/fc/rc.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactor lookup calculation and move hover to end of controlRateConfig_s struct
* moved sbufReadU8 to the bottom
* added sbufBytesRemaining check
* update controlRateProfile version from 6 to 7
* moved thrHover8 declaration position
* revert variable declaration position change
* fixed tests
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Added virtual black box for SITL
* Update src/main/blackbox/blackbox_virtual.c
The platform.h is added into blackbox_virtual,c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Virtual blackbox code style improvement
* Resolved issue of log files counter
* Added logs file name length checking in virtual blackbox
* Added open directory function result checking
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Added computing of const log file neme length
* Improved virtual blackbox file name generation
* Edited errors description in case of using virtual blackbox for non SITL build
* Removed extra #ifdef
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Apply USE_BLACKBOX, USE_BLACKBOX_VIRTUAL define for SITL build
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Code style improvement
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Added USE_BLACKBOX_VIRTUAL checking for #error message
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* consistent autopilot parameter names
- add colons after each blackbox header line
- change alt_hold_throttle_response to alt_hold_climb_rate
- don't use cfg abbreviation for apConfig() because it is harder to search
* enforce semicolon with do... while (0)
* don't abbreviate autopilotConfig to apConfig
* remove semicolon after break to enforce semicolon at input line ending
* explanatory message
* fix copy and paste errors
* restore local cfg alias in place of autopilotConfig()
* struct name formatting as requested by blckmn
Co-Authored-By: Jay Blackman <blckmn@users.noreply.github.com>
* underscore the CLI names, fix prev commit
Co-Authored-By: Jay Blackman <blckmn@users.noreply.github.com>
* Update src/main/fc/parameter_names.h
* Update src/main/fc/parameter_names.h
---------
Co-authored-by: Jay Blackman <blckmn@users.noreply.github.com>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update mag_declination range in settings.c
* Update src/main/cli/settings.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* virtual gps module is added
* USE_VIRTUAL_GPS definition is added to sitl/target.h
* Virtual GPS using are added into sitl and gps modules
* Added settings values for lat, lon, alt, speed, speed3D, course in SITL
* setVirtualGPS function parameters are changed to double
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* code style improvement: undue space symbol deleted
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Code style improvement
* The getVirtualGPS() function declarations is edited
* getVirtualGPS() functions declaration improvement
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* define USE_VIRTUAL_GPS is removed from sitl/target.h
* Revert "define USE_VIRTUAL_GPS is removed from sitl/target.h"
This reverts commit 2e610339c4.
* virtual gps for SITL is made as special GPS_VIRTUAL provider
* Code style improvement. The LF code symbol is added
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* the license is changed
* The license is edited in gps_virtual.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* The license is edited in gps_virtual.h
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Code style improvement
* Virtual gps provider work improvement
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Code refactoring in io/gps.c
* SITL define issue is resolved
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Extra line is removed
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* The VIRTUAL option is added into cli looktable
* switch case tab alignment refactoring in io\gps.c
* wrong indent resolved
* bugfix NMEA and UBLOX GPS mode for SITL (SIMULATOR_BUILD) builds target
---------
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* separate autopilot multirotor from autopilot wing - dummy files for wing
* fix for lisence header for new files
* filling empty PG structures with uint8_t dummy
* autopilot naming, function sharing
* initial position hold setup
* get current gps location
* first position hold draft
* basic control scheme
* add debug values for testing
* first working example with smoothed acceleration
* add deadbands
* Re-organise included files and functions thanks Karate
* revise PID gains
* PIDJ distance controller, not velocity based. Remove airmode check
* sanity check notes
* fix pid bug and improve iTerm handling
* calculate PIDs independently for each axis, increas DJ gains
* adjust pids and smoothing; smoothing cutoff to settings
* force iTerm to zero when close to target
* allow earth referencing in alt and pos hold
* stop activation until throttle raised, but not require airmode
use wasThrottleRaised in place of isAirmodeActivated where airmode isn't really needed
* remove unnecessary debug
* block arming if poshold or althold switches are on
* basic sanity check and OSD warning
* allow user to fly without mag only if they reverse the default
* separate alt and pos hold deadbands
if poshold deadband is zero, sticks are ignored
if user tries to enable posHold and it can't work, they get stick with a deadband
* try to prevent position hold if no mag without valid IMU
fixes a bug in the last commit, also
* retaisn iTerm just attenuate the output
* struct for values
* reset position at start when slowed down, retain rotated iTerm back
* resolve bounceback and remove iTerm attenuation
* adjust PID gains to 30
* force unit tests sto work
* tidy up after merge
* Use mpif
* conditionally only do compass check if Mag is defined
* fixe defines and remove const
* comments to explain strange rc multiplier
* fix small omission when refactoring after throttle raised PR
* licence updates, refactoring from review comments
* fix issues when pos hold deadband is set to zero
* A for acceleration element, not J
* compact the posHoldUpdate() function - thanks K
* rename showPosHoldWarning to posHoldFailure
* Use a function in gps.c to initate the posHold activity on new GPS data
* Use autopilotAngle in place of posHoldAngle
* separate function for gpsHeading truth
* use FLIGHT_MODE(POS_HOLD_MODE) in place of isPosHoldRequested
* removed non-required definitions
* fix failure to initiate position hold from error in ifdef
* refactoring from reviews, rename posHoldReset
* move deadbands for pos and alt hold to their config files.
* comment
* fix for blackbox breakup of GPS values
reverts use a function in gps.c to initate the posHold activity on new GPS data
* fix for msp change for posHoldConfig
* try to constrain aggressiveness at start, smaller deadband
* allow greater overshoot at the start for high incoming speed
rename justStarted to isDeceleratingAtStart
* dynamically update smoothing at the start
* retain iTerm when moving sticks, to keep attitude in the wind
* fix unit tests
* finally retain iTerm correctly while moving sticks, but reset at start
* Fix iTerm reset and parameter rotation
* absolute rotation vs incremental rotation, fix spike after resetting target location
* don't rotate D or A, it reverses their sign inappropriately
* Block yaw, allow in CLI, option to apply yaw correction code
* restore debug
* calc D from groundspeed and drift angle
* add back some target based D
* Earth Frame iTerm vector
appears to work :-)
* fix unit test
* lower PID gains, slowly leak iTerm while sticks move
* earth ref Dterm, not from GPS Speed
smoother than using GPS Speed and heading
* stronger PIDs
* adjust debug
* shoehorn the unit tests
* Proper earth referencing, at last
* clean up a bit
* no need to duplicate wrapping done in sin_approx
* add note about PT1 gain on PT2 filters
* avoid unnecessary float conversions
* Remove unnecessary CLI testing params
* update PID gains, stronger tilt angle correction
* improved distance to target. thanks to demvlad
* Terminate start individually on each axis
added comments
* refactoring to avoid code duplication
* implement reviews, reduce PID gains
* upsampling filter at 5Hz
* warn if posHold mode requested but throttle not above airmode activation point
* disable angle feedforward in position hold
* rebase, pass unit test
* sequential PT1's, refactoring from reviews
* PID and filter revision
* bane of my life
* lenient sanity check, message for noMag, possible DA vector limit code
* replace angleTarget in pid.c only when autopilot is active
* rearrange status checks
* fix debug, tidy up EF axis names, add comments about sign and direction
* stop more cleanly, easier sanity check, phases, debugs complete
* extend sanity check distance while sticks move; refactor; comments
* fix instability on hard stop, allow activation after arming but before takeoff
* make altHoldState_t local, getter to pass unit tests.
* hopefully the last cleanup of this test file
* implement review from PL - thank you!
* restore angle limiting in pid.c , max of 80 degrees allowed in CLI
* fixes after review changes weren't right
* fix braces
* limit max angle to 50 by vector length
* Fix curly brackets, comments and debug mistake
* in autopilot modes, allow up to 85 deg for pos hold
* limit pilot angle in position hold to half the configured position hold angle
* use smaller of angle_limit or half the autopilot limit
* increase alt_hold sensitivity 5x and narrow deadband to 20
* make altitude control 5x stronger with narrower deadband and new name
* add suggestions from recent reviews
* start autopilot gpsStamp at 0
* renaming variables
* reset the upsampling filters when resetting position control
* improved gpsStamp thanks PL
Also cleanup names and notes
* simplify altitude control
* rename to GPS_distances to GPS_latLongVectors
* alt_hold respect zero deadband, hold when throttle is zero
* remove unused debug
* fix unit test
* re-name variables in alt_hold and update comments
* more flexible limit on target vs current altitude
* updates from reviews, thanks karate
* review changes from PL
* more updates from PL review
* rationalise GPS_latLongVectors
* remove static newGpsData and rescueThrottle
* Thanks, PL, for your review
* Modifications, but has a big twitch when sticks stop
* Re-naming, fix the twitch, minor changes
* remove unnecessary unit test reference
* sanity dist to 10m at full stop, send task interval for upsampling filter
* vector and parameter re-name
Co-Authored-By: Jan Post <19867640+KarateBrot@users.noreply.github.com>
* small changes from review
Co-Authored-By: Mark Haslinghuis <8344830+haslinghuis@users.noreply.github.com>
Co-Authored-By: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
* comment PL
Co-Authored-By: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
* fix ltm alt_hold flightMode
* NOINLINE some pid.c functions
* Revert "NOINLINE some pid.c functions"
This reverts commit 56a3f7cec2.
* fast_code_pref the wing functions in pid.c
* use fast_code_pref where won't break the build
* apply fast_code_pref correctly
* NOINLINE some pid.c functions
FAST_CODE_PREF for updatePIDAudio
add comment to FAST_CODE_PREF
FIx platform.h unit test issue
Wing functions all FAST_CODE_PREF
* revert FAST_CODE_PREF changes
* Reduce ITCM RAM footprint considerably
* multiple name changes and some refactoring
Thanks, PL
* small editorial change
* refactoring, thanks PL
Co-Authored-By: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
* 64 bytes to check crossing 180 deg longitude
Co-Authored-By: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
* try to fix build error
Co-Authored-By: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
* Revert "try to fix build error"
This reverts commit f926d26021.
* just guessing here
* Revert "just guessing here"
This reverts commit ebc240a325.
* use a null location at initialisation
* Revert "use a null location at initialisation"
This reverts commit b51ae1395d.
* revert more compact initialisation code due to SITL error otherwise
* fix wrapping when 180 lon meridian is crossed
* null location option from PL
* Revert "null location option from PL"
This reverts commit ad40e979bd.
* refactor PosHold start/stop code
* move Alt_Hold and Pos_Hold warnings ahead of Angle, update some comments
* use setTargetLocationByAxis, fix comments
* change from karatebrot review
Co-Authored-By: Jan Post <19867640+KarateBrot@users.noreply.github.com>
* things still to do
Co-Authored-By: Jan Post <19867640+KarateBrot@users.noreply.github.com>
* keep warning strings 12 or less characters
Co-Authored-By: Jan Post <19867640+KarateBrot@users.noreply.github.com>
* a few more
Co-Authored-By: Jan Post <19867640+KarateBrot@users.noreply.github.com>
---------
Co-authored-by: Jan Post <19867640+KarateBrot@users.noreply.github.com>
Co-authored-by: Mark Haslinghuis <8344830+haslinghuis@users.noreply.github.com>
Co-authored-by: Petr Ledvina <2318015+ledvinap@users.noreply.github.com>
Co-authored-by: Jay Blackman <blckmn@users.noreply.github.com>
* added attitude fields desriptions
* the attitude (imu pitch, roll, yaw) added to blackbox log
* Global variable imuAttitudeQuaternion[3] is added to store current normalized imu attitude quaternion
* IMU attitude quaternion added to log instead of Euler angles
* blackbox logging of IMU attitude quaterions is replaced to GYRO group
* Revert "blackbox logging of IMU attitude quaterions is replaced to GYRO group"
This reverts commit a6020ed6b6.
* code refactoring: use quaternion as global variable instead of float[3] array
* USE_ACC apply for attitude log
* quaterion struct data type is changed to union quaternion_t
* resolved issue of Test module
* Code style improvement: removed empty codes row
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Added STATIC_ASSERT check of quaternion components sequence.
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Code style improvement
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Resolved code issue
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* resolved wrong data type name
* STATIC_ASSERT error resolved
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Improved assert condition
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* added ATTITUDE condition for attitude blackbox log
* added blackbox_disable_attitude cli command
* Attitude position changed in blackbox disabling fields list
* resolved issue wrong quaternion log record condition
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Driver for CADDX camera GM3 gimbal
* Update src/main/cli/settings.c
Fix copy-paste error on variable name.
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/io/gimbal_control.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/io/gimbal_control.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/io/gimbal_control.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Only forward gimbal data with good CRC
---------
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* MSP Range Finder added (configured and tested on the MTF-01P Lidar)
* MSP Range Finder added (configured and tested on the MTF-01P Lidar)
* fix the license of the added files from INAV
* Update src/main/drivers/rangefinder/rangefinder_virtual.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/msp/msp.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/io/rangefinder.h
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/msp/msp.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* refactored the code of INAV for the MSP rangefinder, to be extendable to other MSP rangefinder and more specific about the parameters of the supported ones
* Update src/main/drivers/rangefinder/rangefinder_lidarmt.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/drivers/rangefinder/rangefinder_lidarmt.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactored the code for readability
* mt lidar msp address
* us the delay MS from the dev directly
* todo
* MT device type datatype
* refactored the code for readability
* spacing
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* refactoring
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* after the edits fix
* rm idx
* typo fixed
* i think this shouldn't be here
* spacing
* Update src/main/drivers/rangefinder/rangefinder_lidarmt.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* fix mt models ranges
* remove mt01p model, it doesn't map
* rm "MT01P", it doesn't support map
* rm mt01p, it doesn't support msp
* Update rangefinder_lidarmt.h
* update mt lidar deadzone
* Update rangefinder_lidarmt.c
* Update rangefinder_lidarmt.c
* rm unused variable mtfConnected
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* angle pitch offset (for wings)
* made angle_pitch_offset int16, and changed direction to follow BF convention
* Update src/main/blackbox/blackbox.c
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
---------
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Yaw type rudder or diff_thrust for TPA calculations (for wings)
* Added yaw_type to blackbox header
* KarateBrot review
* KarateBrot break
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
---------
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Altitude control code shared
fewer debugs
subtract D
* remove #include comments, simplify coding, restructuring
thanks JP and MH
* fix cms limits for throttle control
* Use altitude_control debug, fix throttle calculation
minor refactoring
* use AUTO_CONTROL_ALTITUDE debug in place of GPS Rescue throttle pid
* use autopilot for position control names
* fixes from reviews - thanks
* Re-organise included files and functions thanks Karate
* missed init and other typos
* remove old unused unit test file, tidy up thanks Mark
* fix indentation on one line
* tpa speed speed estimation (for wings)
* Some renaming based on Karatebrot review
* Fix with currentPidProfile
* Ledvinap's review
* minor fixes
* Karatebrot and ledvinap review
* Review by haslinghuis
* use idleOffset, simplify idle : check PWM idle
* remove get for dshot idle and calculate it once only
* fixes from reviews, thanks
* use motor_idle for CLI name
* use motorConfig->motorIdle not idleOffset
* rename dshotmotorIdle variable to motorIdlePercent
* small comment improvement
* stop motors after 90 degrees of rotation and with max rate
* handle no accelerometer data
* improve check for acc, although seems to be OK without it
* disable all attenuation if rate is set to zero
* refactoring thanks Karate
* use sensors.h
* remove unnecessary arming check
* exit crashFlip immediately switch is reverted if throttle is zero
* add Crashflip Rate to OSD
* Revert unnecessary changes in crashflip core.c code
and clarify comments about crashflip switch
* update / minimise comments, thanks Karate
* ensure all names say `crashflip` consistently
* Undo quick re-arm because motrors were not reversed
* fix issue with reversed motors, we must disarm
* ignore yaw rotation and set gyro limit to 1900 deg/s
* default attenuation to off (crashflip_rate = 0)
* refactoring, increase rate limit to allow stronger inhibition
* enable in race_pro mode
* don't attenuate on attitude until a significant change occurs
* no attenuation for small changes
* Updates from review by PL
* remove whitespace
* refactor motorOutput, update comments, renaming variables
thanks PL
* changes from review PL
* only permit fast re-arm if crashflip rate set and crashflip was successful
* properly exit turtle mode
* add crashFlipSuccessful to unit test extern c
* small updates from review
* improved crashflip switch handling
* remove unnecessary motors normal check
* rename dMin, remove D_MIN_GAIN_MAX
* rename vars
* fix logic
* fix logic
* Revert "fix tests"
This reverts commit c518c9c444.
* Revert "add yaw and other adjustment cases"
This reverts commit 2cacd4b360.
* Revert "fix unit test"
This reverts commit 3d88f4158a.
* Revert "fix D adjustments change dmax instead of D"
This reverts commit 7ee4e7f8af.
* Revert "Fix telemetry for Spektrum/SRXL (#13814)"
This reverts commit 04fe4b4461.
* review adjustments and test fixes
* Reapply "Fix telemetry for Spektrum/SRXL (#13814)"
This reverts commit eb7f8ee0fd.
* fix logic
* Apply suggestions from code review
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* fix d_max slider
---------
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* TPA_CURVE_HYPERBOLIC (for wings)
* typo fix: tpa_rate_stall_throttle
* ledvinap's review
* fix tpa_curve_expo divider (10 instead of 100)
* Define fixes
* whoops, 16 instead of 1600 for PWL points
* if case for when dividing by zero for hyperbolic expo
* More ledvinap's review
* pow instead of pow_approx + unit tests for hyperbolic TPA
* basic unit tests for classic TPA
* pow was for double. pow_approx for floats is enough
* remove #else from comments
* pow_approx -> powf for hyperbolic TPA
* PWL: brigning back static assert after #13818 PR
* removed extra line per haslinghuis's review
* feedforward update for 4.6
improve jitter reduction method
don't interpolate CRSF protocol
replace 'boost' with highpass element for yaw FF
make yaw highpass element CLI adjustable
add yaw feedforward sustain params to CLI and BBE
refactoring and unit test fix
* implement review suggestions, start on the filter struct
* Attempt PT1 filter init method
* fix silly error, scale time constant correctly
improve gain linearisation at shorter time constants
* fix averaging init
* Review suggestions from PL
* Improve filter initialisation
much better :-)
* re-name prevPacketDuplicate to prevPacketWasADuplicate
* Add review comments - thanks Jan and Mark!
* cast gyro.gyroDebugAxis to int
* A better fix than int cast
* implement review comments from PL
also hopefully improved some comments.
* increase PG to 10, expecting the Disarm PR to use 9
* two always win against one ;-)
* remove inappropriate comment, remove space
* update comments and review suggestions from PL
* Rescedule stats saving on disarm, if quad still moving
* Review suggestions by KarateBrot and Ledvinap
* Moved statsSaveMoveLimit under statsConfig_t
* Add APM32F4 driver libraries and USB middleware
* Add the APM32F405 and APM32F407 target files
* Add APM32 startup files
* Add APM32F4 linker files
* Add APM32F4.mk
* Add APM32 driver files
* Add APM32F40X MCU type
* Sync with the Betaflight master branch and modify the driver directory structure
* Implement CLI on the APM32
* Implement ADC on the APM32
* Implement config streamer on the APM32
* Implement I2C on the APM32
* Implement SPI on the APM32
* Implement DSHOT on the APM32
* Implement transponder ir on the APM32
* Implement serial uart on the APM32
* Implement MCO on the APM32
* Implement DWT on the APM32
* Update the init.c file, adding APM32 MCO configuration
* Remove all duplicated APM32 driver files and retaining only the APM32 LIB directory
* Create APM32F4.mk
* Add linker files for APM32F405 and APM32F407
* Add startup and library config files for APM32F405 and APM32F407
* Add target files for APM32F405 and APM32F407
* Add apm32 MCU driver files
* Add build configuration for APM32 MCU
* Implement config streamer on APM32
* Implement CLI on the APM32
* Implement ADC on the APM32
* Implement RCC on the APM32
* Implement MCO on the APM32
* Implement I2C on the APM32
* Implement SPI on the APM32
* Implement serial uart on the APM32
* Implement IO on the APM32
* Implement DMA on the APM32
* Implement DSHOT on the APM32
* Implement transponder ir on the APM32
* Update init.c
* Add the inclusion of the 'platform.h' file to the APM USB driver source file
* Merge bus SPI duplicate code from APM32 to STM32
* Update timer_apm32.c
* Merge motor duplicate code from APM32 to STM32
* Merge serial uart duplicate code from APM32 to STM32
* Update APM32F4.mk
* Update cli.c
* Update APM32F4.mk
* Remove the apm32_flash_f4_split.ld
* Associate the apm32 linker file with stm32_flash_f4_split.ld
* Disarm on landing
* Changes from review comments, thanks PL
* Sorry missed that one
* calculate Acc magnitude once only, not multiple times
* Include gyro factors as in crashRecovery
* Fix bug in CrashRecovery delta gains
Add temporary debugs to monitor error and delta inputs
* remove 1G subtraction for accMagnitude
thanks Karate
* Use AccDelta or Jerk - thanks Karate
* Revert using Gyro Setpoint and Delta
* Fix typo, thanks Mark
* increment PG version to 9
* Wing TPA gravity factor
* Small corrections according to ledvinap's review (not all yet)
* Some review changes for tpa_gravity
* using throttle after LPF to scale between thr0 and thr100
* tpa gravity further review and fixes
* tpa gravity: removed logging of pitch angle, since it's just pitch
* moved tpa_gravity to the end in pid.h
* KarateBrot review