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

58 commits

Author SHA1 Message Date
Jay Blackman
babfff336d
PICO: Adding PICO tooling to CI (#14503)
* PICO: Adding PICO tooling to CI

* Removing description

* Removing requirement for configs when installing pico_sdk

* Remove requirement for ARM when populating sdks

* Removing exclusion for RP2350 targets

* Adding recursive sub-modules checkout

* Allow for different outputs to only .hex

* Attempt to get SITL bin build to upload as an artifact
2025-07-08 09:15:02 +10:00
Jay Blackman
cb6fc5aabd
REFACTOR: Removing platform specific defines from init.c (#14463)
* REFACTOR: Removing platform specific defines from init.c

* Further MCO improvements

* Adding default
2025-06-22 20:45:50 +10:00
Mark Haslinghuis
c56c350f29
Remove duplicate source file (#14454) 2025-06-19 04:54:50 +10:00
Eric Katzfey
83f9de4247
Remove duplicate files from source.mk (#14448) 2025-06-16 13:21:25 +10:00
Jay Blackman
1dcc611388
PICO: Makefile uf2 support using picotool (#14402)
* Adding picotool build recipe in makefiles.

* Use semaphore in directory for default goal recipe for target

* Suggestions from coderabbitai

* Further coderabbit suggestions

* Wrong case

* Minor change to improve logic

* Further improvements.

- submodules replaced with specific submodule for pico_sdk (to avoid all developers needing this)

* Removing need for remote on git submodule update for configs, as we have the commit occurring daily.

- made sure config also build uf2

* Simplified firmware output selection for target

* Moved UF2 outside of EXST

* Missed two remnants of HEX_TARGETS

* Adding check for target

* As target is known default output can be set in platform mk file or target mk file

 - no need for file indicator (i.e. .exe or .uf2)

* Update config.mk for less verbosity
2025-06-01 04:53:54 +10:00
cvetaevvitaliy
f217ba6d19
Implementation of the ICM-40609D gyroscope driver (#14367)
* 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>
2025-05-27 22:56:37 +02:00
cvetaevvitaliy
b389c2000d
Implementation of the ICM456xx gyroscope driver (#14348)
* add support ICM-45686, ICM45605 gyros

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

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

* update PR issue

* change IMU order

* fix register AAF for Accel, update comments, configure LPF from config

* change IMU order

* fix access to IPREG_TOP1 registers, update define INT1_CONFIG2

* add read Gyro&Acc via SPI DMA

* coderabbitai bot suggestion

Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com>

* fix buf len

* codestyle

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

* coderabbitai bot suggestion: SPI transfer, Inconsistent accelerometer scale setting

* refactor read spi

* update PR issue

* revert "attempts remaining" for gyro detect

* resolve issue

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

---------

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
2025-05-26 12:00:41 +02:00
ke deng
39f82e79df
Change sed search regex to be compatible with BSD sed (#14233)
Change sed search regex to be compatible with BSD sed, # symbol should be escaped.
2025-02-05 22:16:36 +01:00
ke deng
059ada4e4b
Filter comment line while try to get SYSTEM_HSE_MHZ value. (#14194)
* Filter comment line while try to get SYSTEM_HSE_MHZ value.

* use sed to find correct SYSTEM_HSE_MHZ

* get TARGET EXST_ADJUST_VMA value through sed and remove GYRO_DEFINE

* improve get FC_VMA_ADDRESS regex to fit more condition
2025-01-27 21:46:41 +01:00
Jay Blackman
c2768d0409
Refactoring motor to simplify implementation on other platforms (#14156) 2025-01-24 18:37:20 +11:00
Jay Blackman
908a347d2f
Refactor SPI pre init to make it generic and usable from io.h (#14174) 2025-01-24 08:17:28 +11:00
pichim
899ce6731d
Chirp signal generator as flight mode (#13105) 2025-01-21 21:22:35 +11:00
Jay Blackman
5e815ba608
Add ability to specify a config.c file for a config target (#14180)
- adding configTargetPreInit() method to execute code for the config target
2025-01-21 10:58:26 +11:00
Petr Ledvina
9168569d90
config submodule - follow master (#14175) 2025-01-18 04:34:57 +11:00
Petr Ledvina
892da2d46e
Add betaflight/config as submodule (#14158) 2025-01-17 05:14:43 +11:00
Jay Blackman
4069fde56e
Move STM (and clone) related UART implementation to platform (#14128) 2025-01-10 16:13:15 +11:00
Mark Haslinghuis
38928085f2
Adds missing ACCGYRO defines and remove legacy drivers (#14087) 2025-01-01 06:06:39 +11:00
Ivan Efimov
ef81595f1d
Separate autopilot multirotor from autopilot wing - dummy files for wing (#14108)
* 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
2024-12-30 22:36:33 +01: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
Petr Ledvina
0f84c5285d
MAKE - improvement (#14079)
* 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
2024-12-10 22:35:34 +01:00
Jay Blackman
8ef734408f
Adding 'size optimised' file list validity check (#14063)
* Adding 'size optimised' file list validity check

* NL at EOF
2024-12-09 15:49:26 +01:00
timmyfpv
896c8ee29b
Support for apple silicon (M-series) chip. (Right version of Arm GNU toolchain) (#14065) 2024-12-07 07:25:39 +11: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
Jay Blackman
23605feb79
Adding check for speed optimised source validity (#14055)
* 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
2024-12-05 07:28:02 +11:00
Jay Blackman
cfa5f0b2a1
./src/platform stage 3 (#14051)
* Removing more excludes from SITL.

* Ensure platform located files get optimised

* Fix unit test

* Revert file moves
2024-11-28 15:43:25 +01:00
Mark Haslinghuis
1c51c6d903
Bump ARM SDK to version 13.3.rel1 (#14039) 2024-11-26 21:53:38 +01:00
Jay Blackman
53d44aa1b1
Adding common source location in ./src/platform (#14044)
* 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 +=
2024-11-25 21:16:45 +01:00
Steve Evans
0de6278433
Driver for CADDX camera GM3 gimbal (#13926)
* 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>
2024-11-12 20:29:56 +01:00
ahmedsalah52
b70e98ed5a
MSP Range finder added (#13980)
* 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>
2024-11-12 08:42:20 +11: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
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
J Blackman
b21cfe3282
Code re-organisation: src/platform/xxx for the MCU type (#13955) 2024-10-13 03:07:17 +11:00
ctzsnooze
16c157e840
Shared altitude control parameters (#13884) 2024-10-05 16:32:50 +10:00
Jan Post
f71170db1b
Vector library expansion (#12968) 2024-09-16 07:03:32 +10:00
ctzsnooze
254da8f460
Altitude hold for 4.6 (#13816) 2024-09-04 20:29:03 +10:00
Petr Ledvina
3e130de49c
Makefile - remove -j0 (#13838)
Makefile - don't override user-supplied --jobs argument

Some targets will default to parallel build, but only when no
-j / --jobs argument is specified on make command line
2024-08-30 16:12:17 +02:00
J Blackman
5d5697177a
CLEANUP: Removing source wild cards from makefiles (#13834) 2024-08-23 05:59:17 +10: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
Ivan Efimov
8f10f17245
Piecewise linear interpolation routine (#13798)
* piecewise linear interpolation routines

* haslinghuis review

* triling spaces removed

* KarateBrot review

* ledvinap's review

* minor style fixes
2024-08-07 18:21:02 +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
J Blackman
c2c3d6740c
CLEANUP: MCU file locations (#13692) 2024-06-22 09:21:08 +10:00
J Blackman
a84042199d
CLEANUP: small adjustment to the legacy gyro directory (#13693)
* CLEANUP: small adjustment to the legacy gyro directory

* Legacy source explicit declaration.
2024-06-20 19:58:25 +02:00
J Blackman
a49c5c3a35
Adding initial H563 target files in preparation (#13686)
* Adding initial H563 target files in preparation
* Start up files
* Explicit inclusion of source files for @ledvinap suggestion
- adding system_stm32h5xx.c
2024-06-16 12:57:35 +10:00
J Blackman
d82c8facb2
Cleanup HAL usb driver (#13669) 2024-06-11 12:53:33 +10:00
Steve Evans
ab022b0467
Add support for W25N02K 2Gbit/256Mbyte FLASH (#13677)
* Add support for W25N02K 2Gbit/256Mbyte FLASH

* Remove duplicate defintion check

* Rename W25N01G_BB_*_BLOCK macros

* Remove debug

* Create unified driver for W25N01G and W25N02K devices

* Put device parameters in a table

* Add W25N01GV to stacked die driver
2024-06-09 08:30:33 +10:00
Mark Haslinghuis
1074950e42
Update ARM SDK (#12286)
* Update ARM SDK
* Add ARM_SDK_BASE_DIR
* Update ARM SDK to latest 13.2.Rel1
2024-05-30 13:06:42 +10:00
Petr Ledvina
76178a232f
I2C - unify i2cUnstick implementation, improve unstick a bit (#13541)
* I2C - unify i2cUnstick implemntation, improve unstick a bit

Three copies were spread in I2C implementations.

- i2cUnstick is a bit more carefull about clock stretching
- bus status is returned (return true when bus in idle state)

* fixup! I2C - unify i2cUnstick implemntation, improve unstick a bit

* fixup! I2C - unify i2cUnstick implemntation, improve unstick a bit

---------

Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
2024-04-20 17:07:53 +02:00
RoboSchmied
39c4603ac4
Fix typo in [tools.mk] (#13398)
fix typo in [tools.mk]

fix a small typo
tookchain -> toolchain
2024-04-10 09:37:36 +10:00
Károly Kiripolszky
9dfa09a07e
Extend build info with defined flags (#13333)
* Extend build info with defined flags

* Fix CI

* Formatting

* Update license header

* Build options (WIP)

* Review fixes

* Add MSP build info generator

* Review fixes

* Add input hash

* Fix for PascalCase

* Add comment about MSP version
2024-03-21 18:29:22 +01:00