1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00
Commit graph

369 commits

Author SHA1 Message Date
Jay Blackman
0d0c00f341
REFACTOR: Adding DMA_FIRST_HANDLER (#14474)
* REFACTOR: Adding DMA_FIRST_HANDLER

 dmaIdentifier_e could be zero based in the future and align to descriptor array index directly

Also removed unused DMA_INPUT_STRING

* Removed magic number following code rabbit review
2025-06-26 07:34:29 +10:00
Kevin Plaizier
078ffafec1
Add 3+ IMU support (Gyro Fusion) (#14383)
* 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>
2025-06-23 21:35:11 +02:00
Jay Blackman
f45c5c5355
REFACTOR: More platform specific defines moved to platform (#14471) 2025-06-23 10:07:49 +10:00
mjs1441
2c378e96a0
CLI allow for DEFIO_PORT_PINS pins per port. (#14460) 2025-06-19 05:48:31 +10:00
Eric Katzfey
a94083e77d
Removed extraneous parentheses to resolve compiler warning (#14441) 2025-06-15 04:24:31 +10:00
Steve Evans
62dd5f6e4c
Add missing OCTOX8P definition (#14418) 2025-05-30 21:55:04 +02:00
Osiris Inferi
e9adc03a97
Move flash_read arguments around in CLI help (#14404) 2025-05-23 18:15:49 +02:00
Petr Ledvina
99e8dd8840
Fix virtualled (#14276) 2025-03-01 17:40:02 +11:00
Petr Ledvina
b96c0b69cb
CLI - prevent serial overflow (#14251)
use serialWriteBufBlocking for cli, busy-waiting if TX buffer is full
2025-02-11 15:57:21 +01:00
Petr Ledvina
b277364b2c
Refactor missing prototypes 2 (#14170) 2025-01-29 06:20:12 +11:00
Mark Haslinghuis
bbaf961edb
Add 230K4 baudrate support for GPS (#14192)
* Add support for 230K baudrate for GPS

* Update CLI

* Use invalidName for all instances
2025-01-24 18:15:54 +01:00
Jay Blackman
c2768d0409
Refactoring motor to simplify implementation on other platforms (#14156) 2025-01-24 18:37:20 +11:00
Mark Haslinghuis
9db36f66d9
Fix GPS UART representation (status command) (#14193)
Fix GPS UART representation
2025-01-23 23:03:00 +01:00
Jay Blackman
cec5d00bbf
Remove MCU name table from CLI (rely on build info), add MCU info MSP2 command (#14148) 2025-01-18 04:17:57 +11:00
Jay Blackman
c91e4214eb
FIX: Adding RP2350B as MCU type and correcting lookup table error (#14138) 2025-01-11 06:01:04 +11:00
Jay Blackman
31bd403446
Adding support for UART0 (#14094) 2024-12-28 16:55:15 +11:00
Petr Ledvina
ac82d8b998
Refactoring of PR 13050 - support for custom OSD messages from external device (#14097) 2024-12-22 15:44:08 +11:00
ahmedsalah52
d244239f39
opticalflow mt sensor added (#14038)
* opticalflow mt sensor added

* set the processedFlow to raw when no rotation

* use sin and cos approximations

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/sensors/opticalflow.c

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* refactoring

* not needed anymore

* update

* Update src/main/sensors/opticalflow.c

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/sensors/opticalflow.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>

* update

* rm prototype

* clean up

* Update src/main/drivers/opticalflow/opticalflow.h

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/drivers/opticalflow/opticalflow.h

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* update flip_y

* Update src/main/drivers/opticalflow/opticalflow.h

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/drivers/rangefinder/rangefinder_lidarmt.c

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/drivers/rangefinder/rangefinder_lidarmt.h

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/sensors/opticalflow.c

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/sensors/opticalflow.c

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* Update src/main/sensors/opticalflow.c

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* rm casting

* update op rotation

---------

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
2024-12-21 05:47:36 +11:00
Mark Haslinghuis
4b78aeec51
Fix arming disable flag and OSD warning buffer size (#14057)
* Fix missing arming disable flag

* Add test for array length

* Fix array init && add getter

* armingDisableFlagNames is no longer external

* Update array

* Thanks ledvinap

* Revert designated initializers

* Increase OSD Warnings buffer size

* Remove standard libraries

* Refactor

* Update pos

* Restore comment

* Micro optimize

* Extract condition

* Another optimization

* Use cmpTimeUs (not cmp32)

* Revert STATIC ASSERT string change

* Adjust esc sensor warning

* I like this

* Optimize intended minimum width

* revert Optimize intended minimum width

* Is dshot telemetry and esc telemetry exclusive

* Fix conflict

* OSD - WARNINGS_PREFERRED_SIZE

* OSD - Return NONE for no flag
2024-12-06 15:33:25 +01:00
ctzsnooze
3138141cd1
Position hold for 4.6 and Altitude Hold updates (#13975)
* 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>
2024-12-06 13:04:00 +11:00
nerdCopter
ed6a4a4769
duplicate emptyline removal (#14027)
* trailing space removal

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>

* deduplicate empty lines

---------

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
2024-11-15 23:07:25 +01:00
nerdCopter
493b9bf819
trailing whitespace removal (#14026)
trailing space removal

Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
2024-11-15 22:19:13 +01:00
Petr Ledvina
246d04dc57
Refactor uart (#13585)
* 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
2024-11-04 22:07:25 +01:00
cvetaevvitaliy
715c1671a8
Add support external clock for gyro ICM42688P (#13912) 2024-10-24 06:49:18 +11:00
ctzsnooze
58fc8bbbb8
Shared altitude control function in position_control.c (#13954)
* 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
2024-10-16 23:17:44 +02:00
ctzsnooze
16c157e840
Shared altitude control parameters (#13884) 2024-10-05 16:32:50 +10:00
J Blackman
c2900de5c1
Adding CLI command pass through for MSP (#13940) 2024-10-03 23:59:47 +10:00
ctzsnooze
776e8c7b3c
Refactor Rx code and better support 25Hz links (#13435)
* RX task update rate to 22Hz, to improve 25Hz link stability

* modified Rx code

* add LQ to debug

* use max of frameAge or FrameDelta

* Require a dropouit of 200ms, not 100ms, before RXLOSS

* remove FrameAge, use 150ms timeout 50ms checks

* fix tests and tidy up the comments

* Handle NULL input as before, log frame time

* possible solutions to review comment about names

* Remove rxFrameTimeUs

- prepare for direct use of lastRcFrameTimeUs
- refactor rx_spi callback

* remove global currentRxRateHz

* simplify updateRcRefreshRate

* re-name to recheck interval, return frame time debug

* Calculate RxRate only once

* use rxReceivingSignal for consistency

* use signalReceived not rxDataReceived for consistency

* suggestions from review PL

* move defines, thanks K

* fixes from review, thanks MH

* review changes, undo task interval change

rename bool rxIsReceivingSignal to isRxReceivingSignal
thanks Steve for resolving that tasks changes are not needed
thanks PL for your feedback also

---------

Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
2024-10-01 09:23:24 +10:00
J Blackman
331801c7a2
Minor CLI update to give a noreboot option so save and exit (#13904)
* Give a -n option to exit CLI

- means you can set any serial port to MSP, and then activate CLI on it using #, with an "exit -n" to return to MSP mode without a reboot required.
- https://webserial.io is a great utility for using CLI outside the configurator.
- future changes will include possible multiple CLIs being active at the same time, along with debug printf from anywhere in the code to an active debug cli.

* Altered to strcasecmp, and changed param required to noreboot

* Adding additional details to the commands
2024-09-26 14:30:57 +02:00
Kiss Ultra
a6d70be96a
Fixes #13220: Fix kiss esc passthrough, Fix castle (escprog cc) command. (#13911)
* Fix kiss esc passthrough, Fix castle (escprog cc) command.

* Update src/main/drivers/serial_escserial.c

Thank you.

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

---------

Co-authored-by: Alex Fedorov <fedor@anuta.org>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
2024-09-21 02:32:46 +02:00
Petr Ledvina
952ccb68c4
cli - fix gpspassthrouh when GPS port is not open (#13878)
- return status from gpsPassthrough
- test gpsPort
2024-09-06 09:46:51 +02:00
luckk
6dcc268918
Add apm32f405/f407 support (#13796)
* 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
2024-08-19 08:34:31 +10:00
Alexander
fcecabf01e
Fix searching a resource (#13826)
If you add a new resource whose name starts with an existing resource name it won't be found. For example if you add `PWM_EX` resource after `PWM` you won't be able to store a pin into it. So when you execute `resource PWM_EX 1 A01` it will be stored into `PWM`.
2024-08-17 20:25:39 +02:00
J Blackman
5762688f6d
CLEANUP: Move flash drivers to their own directory (#13691)
* 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
2024-06-25 16:24:40 +02:00
Petr Ledvina
286cfb5022
Improve features (+ cli) (#13494)
* Features - refactor featureNames[]

Use designated initializers for used features. NULL values are stored
in gaps.
Use ARRAYLEN() for featureNames iteration
Use `unsigned` for bitmasks

* Features - add featuresSupportedByBuild

bitmask of features that are supported in current build
configuration. Copied from init.c sanitization

* Features - simplify feature sanitization code

featuresSupportedByBuild makes things much easier

* Features - improve cli feature handling

- refuse all features that are not compiled in
- AlreadyDisabled/AlreadyEnabled info
- refuse operation if multiple features match

* fixup! Features - improve cli feature handling

* Features - print available and not supported features separately

* Update src/main/cli/cli.c

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* features - print full state without command

---------

Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
2024-05-20 16:03:19 +02:00
Petr Ledvina
dac4939215
beeper - minor refactoring (#13610) 2024-05-17 20:19:01 +10:00
Mark Haslinghuis
5a28ce5129
Make Cppcheck happier revived (#13566)
Co-authored-by: Štěpán Dalecký <daleckystepan@gmail.com>
2024-05-10 13:23:32 +10:00
Petr Ledvina
4640a5da96
cppcheck - minor problems fixed (#13609) 2024-04-30 14:04:28 +02:00
Petr Ledvina
d447d795f4
Improve unittest build system (#13554)
* unittest - fix duplicate symbols in unittests

Some symbols were declared again
With clang -fcommon, this resulted in allocatin in common segment and
prevented error.
(tentative definitions in C standard).
-fno-common (now default in clang https://reviews.llvm.org/D75056)
causes compilation errors.

Declarations are now marked extern.

* unittest - fix scheduler array size for unittest

Unittest needs extra space for canary

* unittest - fix missing include (needed for clang-16)

* unittest - remove unused varibles

-Werror in clang 15+

* unittest - increase max supported version to clang-16

* unittest - conditionaly disable useless output in unittests

* unittest - C++11 version of STATIC_ASSERT

* unittest - fix initializers for g++

- Change order of initializers to match order in struct
- make valueTable initializion consistent (necessary for C++)
- adapt controlRateConfig

* unittest - adapt scheduler_unitest for g++

scheduler_stubs.c is necessary to initialize task_attributes

* unittest - fix ledstrip unittest

only part of config was zeroed

* unittest - fix g++ warnings

- memcpy when length is known and \0 is not copied
- isError is local stub, no extern
- serialReadStub - don't memcpy into object, use initializer

* cli - cleanup cliGetSettingIndex

- compare only passed bytes (old version may read data after
name)
- input string is const

* unittest - fix ld warning from PG sections

move pg data sections after .rodata. Sections were marked as writable
due to relocation (!?). That marked .text output section
(containing .pg_data) as writable too and linker correctly complained
that executable section is writable.

* unittest - cleanup

* unittest - adapt after code cleanup, add gcc

- remove clang flags that are not necessary now (tested on clang-11
and clang-16)
- add support for gcc ( make test CC=gcc CXX=g++ )
- add suport for different optimization level (detects some code
problems) : make test OPTIMIZE=-O2
- fallback to clang on Linux too

* fixup! unittest - conditionaly disable useless output in unittests
2024-04-22 22:43:24 +02:00
Mark Haslinghuis
d20d42dd48
Fix index and ability to configure LPUART_RX due to typo (#13565)
* Fix typo

* Fixes per review
2024-04-22 21:04:31 +02:00
Petr Ledvina
4ae1a672b4
Fix clang unitests (#13551) 2024-04-21 16:51:23 +10:00
Mark Haslinghuis
90841282b0
Add resource for LPUART (#13306)
* Add resource for LPUART

* Fix per review

* Fix per review 2
2024-03-27 09:57:02 +01:00
StNekroman
413d05d6c4
Make servos great again (#13451)
* Make services great again

* Make servos great again

* Changes according comments
2024-03-14 20:50:16 +01:00
Mark Haslinghuis
6d98dbb742
Fix space in status output when gps version is unknown (#13423)
* Fix space in status output when gps version is unknown

* Refactor per review
2024-03-07 12:09:42 +01:00
Jan Post
5fff78136e
Fix CLI command "bind_rx" for CRSF (#13267) 2024-01-05 14:31:30 +11:00
Steve Evans
6af1614a5d
Fix dma pin <io> list (#13233) 2023-12-18 21:11:31 +01:00
Mark Haslinghuis
65aaf732f9
Remove custom defaults and enable features on boot (#13216)
* Remove custom defaults

* Fixes per review

* Fixes per review (thanks ledvinap)

* Fix copy pasta
2023-12-17 07:58:15 +01:00
Jan Post
5769b3021e
Dshot RPM Telemetry Refactoring (#13012) 2023-12-03 15:16:35 +11:00
Eike Ahmels
083b595617
M10 ValSet support, unit connection and reconnect stability (#12799)
* WIP

* start of implement m10 code

* Fetch MON-VER from unit to check for unit version

* test nav5 m10 command

* missing empty lines

* offload detect to config file

* copy from hasli and organization

* fix platform.h include

* fix cli_unittest gps include

* fix cli_unittest for gps calls

* guard ublox version in gpsData

* print human readable hw version

* add utc_standard param and transfer with nav5 set
add nav5x message for autonomous mode for m10

* fix typo

* revert order structure, remove functions and reduce flash size

* revert order structure, remove functions and reduce flash size

* fix gps init and navx5 message

* generalized nav5 message

* remove unguarded debug

* change ubx version detection, baud rate negotiation fix and save found baud

* revert indentation

* revert indentation and refactorings

* the new code works with faster baud rate changes

* remove unguarded debug statement

* fix cli commands, major space reduce finished, removed extensions for now

* ubx version checks, add valset for M10

* beta of valset, change suggestions from ledvinap and macgivergim

* valset helper function and combine set nav rate valsets

* more valset refactoring

* remove big array and replace with macro

* remove assert, as it can stop bf completely

* refactoring to offsetof

* making reconnect more resilient, reorganize rate setup, so it doesnt get missed on init

* improved lost communcation detection, dont rely on ACK/NACK anymore

* paket rate debug

* adding debug mode, fixing major flight mode bug

* revert fake flight "isConfiguratorConnected"

* fixed proto detection, fixed reconfigure on too low updaterate

* valset doesnt always send ACK, so we dont wait for it

* size optimization, debug mode rename, minor fixes

* implemented some requested changes

* changed wait delay millisecond based

* fixes from ctzsnooze and zzXyz

* timer fixes

* CamelCase new settings names

* indent

* Fix failure to enter flight model on GPS Fix

* remove old commented out debugs

* simplify timeouts

* Clarify skip_acc and remove development valset code

* accept PL's advice to remove  >> (8 * 0

* Simplify package counter, remove reconfiguration based on packet count

* fix error in package count introduced in previous commit

* Fix delay detecting Configurator, ANA disable (for another PR)

* address payload comments and fix logical error

* indentation edits

* delete old enum

* log gps and firmware nav interval times

* fix payload size, inc Rx buffer to 256, ifDef for sw_proto

* remove token parsing (Petr suggestions)

* fixes from reviews

* Basic NMEA improvements

* Address comments from karate

* only check platform version - thanks zzyzx

* Fix for too many sats problem - thanks zzyzx

* tidy up comments, ifdef some ublox definitions

* Use Nav packet intervals, NMEA and UBX, for time delta

* Resolve comments and flatten conditionals

* editorial change

* single function for gpsSol.navIntervalMs

* adam-ah suggestion for payload optimisation

* ACK/NAK & polled message timer fixes

* Revert timer fixes - unexpected side effects

* Revert adam-ah suggestion for payload optimisation"

This reverts commit 42fc8c04fdbc436c9ef196b88f0764ffcbb9239f.
Broke the display of sat info when more than 32 sats in view

* implement a number of comments

* Fast task rate on new data, don't spam at the start

thanks adam-ah

* include PDOP for M10 via NAV-PVT

* Address some of PL's recent comments

* don't recalculate millis so many times

* tidy up baudrate connect code

* Split receiving of GPS bytes from processing by adding GPS_STATE_PROCESS_DATA

* Split receiving of GPS bytes from processing by adding GPS_STATE_PROCESS_DATA

* Preserve state whilst processing packets

* Set gpsData.state directly as gpsSetState() clobbers gpsData.state_position

* Restore original read time check

* Schedule gpsUpdate() to run immediately again when a packet is received for processing

* add debugs to display scheduler valuesl

* simpler scheduler solution

* minor debug change

* FIxes: M10 connection, pDop, NMEA disable; thanks zzyxz

NB: Breaks unit's neat reconnection methods
M8 need a lot of settling time before using the serial port

* ubx parse length sanity + cleanup + dashboard conditional compiles

* Address recent comments from PL

---------

Co-authored-by: ctzsnooze <chris.thompson@sydney.edu.au>
Co-authored-by: ZzyzxTek <zzyzx@zzyzxtek.com>
Co-authored-by: Steve Evans <Steve@SCEvans.com>
2023-08-12 12:10:55 +10:00
J Blackman
d5d3ee88be
Removing STM specific defines from common_pre, and other cleanups (#12982)
Removing STM specific defines from common_pre, and other cleanup
2023-07-27 11:34:28 +02:00