* Allow for 3 gyros to be fused at once.
* Handle the case where no GYRO_COUNT is defined
* Fix accel init bug
* Fix bugs found by AI
* Fix compile time assert message
* Move to picking which IMU you want to enable, allow IMU that have the same scale and looprate to run together even if they aren't identical IMU.
* Fully support 8 IMU
* Fix suggestions, except for MSP all suggestions
* Fix bugs found by AI
* Update gyro_init
* Fix unit tests (feels wrong though)
* Allow MSP to update all gyro alignment
* resolve comments
* Only auto set up to 4 gyros in a config.
* Update MSP implementation
* Fix divide by 0 error
* Update src/main/target/common_post.h
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Handle case where gyro 1 does not exist
* Fix 426XX driver
* fix = logic in if statement
* Update src/main/msp/msp.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/drivers/accgyro/accgyro_spi_icm426xx.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Apply ledvinap suggestions
* Fix detectedSensors initialization
* fix getGyroDetectedFlags
* Automatically handle GYRO_COUNT for up to 4 IMU
* better handle unit tests
* Backwards compatible with older config.h files
* Update src/main/sensors/gyro_init.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/target/common_pre.h
Co-authored-by: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
* Update src/main/sensors/gyro_init.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/sensors/gyro.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* This needs to be the case or unit tests fail, without this we cannot choose default gyro either.
* ledvinap suggestions
* whitespace
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Co-authored-by: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
* Allow for builds with certain features disabled.
Fix build for when the following are disabled:
USE_DMA
USE_DSHOT_TELEMETRY
USE_SERIAL_PASSTHROUGH
* Tweak #ifdef / UNUSED as per code review.
* 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>
* 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>
* Fix PG ID
* Fix corruption in MSP_SET_SENSOR_CONFIG
* No need to specify ammount of bytes remaining
* Update after review from @ledvinap
* Remove unused PG_BETAFLIGHT_END
* 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>
* 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>
* 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
* 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
* 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>
* CLEANUP: Move flash drivers to their own directory
* Missed flash_w25q128fv.h.
* Directories in #include, and specifying all source files explicitly.
* Revert RX driver src file implicit declaration