* Don't handle non-MSP characters on VTX MSP port
* Remove check for CLI active on VTX MSP port as it can no longer be enabled
* Only include check for MSP display port if USE_MSP_DISPLAYPORT is defined
* MAKE - improvement
- specify SDK file for each target pair on linux and macosx
- verify checksum before unpacking downloaded file (curl ignores server
certificate)
- infer ARM_SDK_DIR from SDK file name
- detect installed SDK, checking that it is newer than downloaded
file (.installed file in SDK dir)
- fix unzip on windows (doubly nested SDK directory was created)
* MAKE - fix .zip handling
* MAKE - unintended space on windows
* 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>
* Adding check for speed optimised source validity
* Updated file location
* Common files to all HW
* Inadvertent inclusion
* VPATH reductions
- note simulator directory name change due to clash with MK file.
* Missed these MK files.
* Remove empty string
* Adding common source location in ./src/platform
To enable the continued clean up of multiple files still in ./src/main/driver (more PRs to follow) that are specifically for AT32, APM32 and STM32
Source will be moved to MCU_COMMON_SRC where it is specifically for that MCU (or variant). The test will be to ensure no files in the MCU_EXCLUDES for SITL.
* Use of +=
* 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>
* VCP - zero-init USB port in usbVcpOpen
* Serial - serialPortIdentifier_e is signed
* UART - remove unused serialPortCount
* UART - allow compiling spectrum without UART
* UART - minor improvements
closeSerialPort tests for NULL,
no other functional changes
* serial - refactor serial resource handling
- port related resources (tx/rx/inverted,dma)
- are stored sequentially, with space in place of ports that are not
enabled (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT +
RESOURCE_SOFTSERIAL_COUNT)
- RESOURCE_UART_OFFSET, RESOURCE_LPUART_OFFSET, RESOURCE_SOFTSERIAL_OFFSET
- resource entries are pointing into this array (UART, LPUART, SOFTSERIAL)
- both pins and DMA
- inverter is supproted only for UART + LPUART (makes sense only
for UART, to be removed)
- softSerialPinConfig is removed, it is no longer necessary
- serialResourceIndex(identifier) is used universally to get correct
index into resource array
- unified handling of resources where possible
- serialOwnerTxRx() + serialOwnerIndex() are used for displaying resources
correctly to user.
- serialType(identifier) implemented
- serialOwnerTxRx / serialOwnerIndex are trivial with it
- large switch() statemens are greatly simplified
* serial - merge code duplicated in all UART implementations
- drivers/serial_uart_hw.c contains merged serialUART code.
Code did not match exactly. Obvious cases are fixed, more complicated
use #ifs
- pin inversion unified
- uartOpen is refactored a bit
* serial - refactor uartDevice
- use 'compressed' enum from uartDeviceIdx_e. Only enabled ports are
in this enum.
- uartDeviceIdx directly indexes uartDevice (no search necessary, no
wasted space)
- use `serialPortIdentifier_e identifier;` for uartHardware
- for DMA remap, define only entries for enabled ports (uartDeviceIdx_e
does not exist disabled port)
* serial - apply changes to inverter
New implementation is trivial
* serial - HAL - rxIrq, txIrq replaces by irqn
There is only one IRQ for serial
* serial - serial_post.h
Generated code to normalize target configuration.
jinja2 template is used to generate header file. Port handling is
unified a lot.
SERIAL_<type><n>_USED 0/1 - always defined, value depends on target configuration
SERIAL_<type>_MASK - bitmask of used ports or given type. <port>1 is BIT(0)
SERIAL_<type>_COUNT - number of enabled ports of given type
SERIAL_<type>_MAX - <index of highest used port> + 1, 0 when no port is enabled
* targets - remove automatically calculated valued from configs
serial_post.h generated it
* serial - remove definitions replaced by serial_post.h
* serial - change LPUART to UART_LP1 in places
LPUART is mostly handled as another UART port, this change reflects it
* serial - use ARRAYLEN / ARRAYEND in some places
replaces constant that may not match actual array size
* serial - adapt softserial to changes
* serial - whitespace, comments
* softserial - fix serialTimerConfigureTimebase
* serial - suspicious code
* serial - unittests
* serial - cleanup
* serial - simpler port names
Is this useful ?
* serial - no port count for SITL necessary
* serial - fix unittests
include serial_post.h, some ports are defined, so normalization will
work fine
* timers - remove obsolete defines from SITL and unittests
* serial - cosmetic improvements
comments, whitespace, minor refactoring
* serial - fix serialInit bug
serialPortToDisable was preventing further tests
* serial - fix possible NULL pointer dereference
* serial - move serialResourceIndex to drivers
* serial - refactor pp/od and pulldown/pullup/nopull
Centralize serial options handling, decouple it from MCU type
Move some code into new drivers/serial_impl.c
* serial - make port.identifier valid early in port initialization
* serial - fix unittest
Code is moved around a bit to make unittests implementation easier
* serial - bug - fix off-by-one error
uart1/softserial1/lpuart was not working properly because of this
* serial - whipespace + formating + style + comments
No functional changes
* utils - add popcount functions
Wrap __builtin_popcount for easier use. Refactor existing code using
it. Update code using BITCOUNT macro in dynamic context (BITCOUNT is
for compile-time use only)
* serial - inverter - simplify code
* pinio - prevent array access overflow
* serial - refactor SERIAL_BIDIR_*
SERIAL_BIDIR_OD / SERIAL_BIDIR_PP
SERIAL_PULL_DEFAULT / SERIAL_PULL_NONE / SERIAL_PULL_PD
* serial - simplify code
minor refactoring
- cleaner AVOID_UARTx_FOR_PWM_PPM (unused anyway)
- serialFindPortConfiguration* - remove code duplication
- use serialType in smartaudio
* serial - add port names
- const string is assiociated with each compiled-in port (easy to pass around)
- findSerialPortByName
* cli - improve serialpassthrough
- support port options (in current mode argument)
- support port names (`serialpassthrough uart1`)
- improve error handling; check more parse errors
* cli - resources - minor refactor
- prevent SERIAL_TX_NONSENSE when parsing resource type
- fix possible NULL pointer dereference
- store resource tag only after checking all conditions
- slighty better error reporting
- `resource serial_tx 1` will print resource assignment
* serial - remane pulldown to SERIAL_PULL_SMARTAUDIO
Make sure nobody uses it by
mistake. SERIAL_PULL_SMARTAUDIO_SUPER_DANGEROUS_USE_AT_YOUR_OWN_RISK_THIS_WILL_BREAK_EVERYTHING_AND_KILL_YOUR_PET_FISH
would be better choice, but try shorter version first.
* smartaudio - minor refactor/improvement
- Fix softserial on AT32
- make it easier to handle SA on per-cpu basis
* softserial - minor refactoring
no functional changes
* UART - move AF handling before MCU dependent code
* UART - adapt APM32 / APM32F4 code
- Modeled after F4 where possible
- come code moved from APM32 to APM32F4, possbily not necessary, but
it improves similarity with STM32F4
* UART - APM32 - remove per-pin AF
* UART - APM32 - bugfix - fix pinswap #if conditions
* UART - apply some improvemnts from APM32 to STM32
* UART - add todo for F4 serial speed
* UART - fix typo
* UART - refactor support for USE_SMARTAUDIO_NOPULLDOWN
* UART - typos, comments, minor improvements
* UART - move code into enableRxIrq
TODO: split into mcu-specific filer (but in sepatate PR)
* UART - add UART_TRAIT_xx
makes #if test easier and more consistent
more traits shall follow
* UART - fix variable name
unused branch, would trigger compilation error otherwise
* UART - use tables instead of switch
* UART - smartaudio
minor style change + better comments
* UART - unify mspPorts iteration
* UART - fix spelling
* UART - another typo
* UART - fix serialResourceIndex
offset must be added, not subtracted
offset can be negative
* UART - fix typo
Bad day ...
* UART - use const table
GCC does optimize it better.
Should not cause functional change
* UART - use OwnerIndex for inverter
- 1 based
- only UART has inversion
* UART - refactor serial_resource a bit
Single table + helper function. New table is easier to read
* UART - serial_impl header is necessary
* UART - style-only changes
typos
unify whitespace
comment improvement
add some const modifiers
use cfg in uartConfigureDma
minor improvemnt of for loops
* UART - remove LPUART inverter
LPUART always supports internal inversion, code was incomplete and
unused
* UART - update jinja template, regenerate files
* UART - enable UART module RCC clk before configuring DMA
Does not change anything, UART RCCs are enabled unconditionally
* 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>