* set default of spec prearm screen to false if race pro not defined
* Simple variant - thanks Ledvinap
---------
Co-authored-by: Eike Ahmels <ea@weslink.de>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* 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>
* Baro and Mag driver check for I2C bus being busy
* Update src/main/drivers/bus_i2c_busdev.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
---------
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Config - add error checking into config_streamer.c,
CONFIG_STREAMER_BUFFER_SIZE does not match actually writen data in
some cases
* Config - fix buffer read ovefrflow
CONFIG_IN_RAM and CONFIG_IN_SDCARD used 4 byte byffer, but 32 bytes
got actually copied
CONFIG_IN_MEMORY_MAPPED_FLASH used 8byte buffer, but but 32 bytes
got actually copied
* Config - add write functions into header
---------
Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
* Add ez_landing_speed parameter
The parameter is the speed at which ez_landing will be effectively disabled in tenths of meters per second.
Default value 50 (5 m/s).
EZLANDING bug field 5 is the contribution from this parameter to the ezlanding throttle cap.
* Correct ez_landing_speed logic and scaling
* ez_landing_speed should now raise the limit when the speed is above ez_landing_speed (previously only raised the limit if the speed was bellow, and had no effect above the limit)
* ez_landing_speed should now be scaled so that EzLanding is effectively disabled when speed >= ez_landing_speed (previously EzLanding would be disabeld when speed was at half of ez_landing_speed)
* Add stick input upper limit as EZLANDING debug 4
* Check for gps 3D fix before using gps speed for EzLanding
* Prevent division by 0 if ez_landing_threshold is set to 0
* Scale EzLanding speed to m/s from cm/s
* Update src/main/flight/mixer.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* mag cal improvements
reduced threshold to start updating the previous cal
LED0 goes 'solid' only when the calibration start threshold is met
Don't zero previous Cal values until the update threshold is met
Mag_calib debug shows cal values at zero unltil they start being updated.
* beep ready, acc_calibration, and gyro_calibrated, for audio feedback
s
* improvements, thanks to feedback from PL
* change magCalEndTimeUs to magCalProcessEndTimeUs
* make process names more obvious
* use static boolean for initation and termination
* magCalProcessEndTimeUs to magCalEndTime
* LED ON, not toggle
* ensure that division is a float
* change logging, improve logic for recalibration
* Increase sensitivity, smooth center, higher max cogYawGain, renaming
* use non thrust vector maths, revise and add comments
* three factors to reduce ez_ef - speed, thrust vector, stick movement
re-naming and comments
* fix unittest, update comment
* normalize heading magnitude, add pitch and roll suppression factors
* ignore pitch factor on wings
because they 'normally' have forward velocity while flat
and their path while rolled usually does not change abruptly
* fix unit test
* fix dumb mistake blocking pitch suppression for non-wings
* fixes from review thanks PL
* refactor vector2normalize - thanks to karate
* Use X and Y for 0 and 1 in rMat
* Revert debugs, update comments from review
* lrintf for floats in debugs
* vector.h - implement some vector2* code as vector*
* Refactor IMU code
Move compass and Cog code into separate functions, separate gain
heuristics
- imuCalcGroundspeedGain
- imuCalcCourseErr
- imuCalcMagErr
Temporary refactor od imuDebug_GPS_RESCUE_HEADING, to be removed of optimized
* Simplify simulator build conditional compilation
* Adapt unittests to IMU after refactoring
* Maybe fix the test?
=
* Update src/main/flight/imu.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/flight/imu.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/flight/imu.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/flight/imu.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Update src/main/flight/imu.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
---------
Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Add support for GoerTek SPA006_003 barometer - based on DPS310
* Fix missing coefficients
* Fix tabs
* Fix per review Ledvinap
* Add missing coefs for pressure calculation
* Use chunk size of 9 bytes
* Fix MIN
* Update comment
* Be more explicit
* Update src/main/drivers/barometer/barometer_dps310.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
---------
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
Data registers are locked until last/unlock register is read. New data
are not stored when locked and DRDY is not set.
On bus error, read may finish early (not reading unlock register) and thus
cause driver lockup.
Co-authored-by: Petr Ledvina <ledvinap@hp124.ekotip.cz>
* Use intptr_t for casting void * to an integer
* Update src/main/cms/cms.c
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* ensure that return altitude is not negative with current height mode
* Update src/main/flight/gps_rescue.c
* Update src/main/flight/gps_rescue.c
* Update src/main/flight/gps_rescue.c
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Add uartWriteBuf() to improve performance
Optimised transmit buffer space check
Tidy up group duration calculations
Add uartBeginWrite, uartEndWrite and serialWriteBufNoFlush
Remove OSD grouping and check on the fly. Implement multi-pass artificial horizon rendering.
Fix rendering of camera frame
Fix stick overlay background rendering
Fix channel rendering
Fix ESC information rendering
Make Spec Prearm Display deterministic
Co-authored-by: Petr Ledvina <ledvinap@gmail.com>
* Fix openocd makefile target by using TARGET_MCU_FAMILY
The condition before this commit in mk/openocd.mk
ifeq ($(TARGET_MCU),STM32F4)
OPENOCD_CFG := target/stm32f4x.cfg
else ifeq ($(TARGET_MCU),STM32F7)
OPENOCD_CFG := target/stm32f7x.cfg
else
endif
ifneq ($(OPENOCD_CFG),)
OPENOCD_COMMAND = $(OPENOCD) -f $(OPENOCD_IF) -f $(OPENOCD_CFG)
endif
resulted in a not defined OPENOCD_COMMAND, because TARGET_MCU does not
contain the MCU family such as STM32F4, but e.g. STM32F411xE.
Thus executing e.g (note: CONFIG=BLACKPILL411 is a custom config I created for the Blackpill Board)
$ make DEBUG=GDB CONFIG=BLACKPILL411 openocd-gdb
make: *** No rule to make target 'openocd-gdb'. Stop.
whereas after the patch:
$ make DEBUG=GDB CONFIG=BLACKPILL411 openocd-gdb
...
...
Linking STM32F411_BLACKPILL411
Memory region Used Size Region Size %age Used
FLASH: 7680 B 16 KB 46.88%
FLASH_CONFIG: 0 GB 16 KB 0.00%
FLASH1: 329297 B 480 KB 67.00%
SYSTEM_MEMORY: 0 GB 29 KB 0.00%
RAM: 62612 B 128 KB 47.77%
MEMORY_B1: 0 GB 0 GB
text data bss dec hex filename
331757 5220 56980 393957 602e5 ./obj/main/betaflight_STM32F411_BLACKPILL411.elf
openocd -f interface/stlink-v2.cfg -f target/stm32f4x.cfg & ./tools/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gdb ./obj/main/betaflight_STM32F411_BLACKPILL411.elf -ex "target remote localhost:3333" -ex "load"
Open On-Chip Debugger 0.12.0
Licensed under GNU GPL v2
For bug reports, read
http://openocd.org/doc/doxygen/bugs.html
WARNING: interface/stlink-v2.cfg is deprecated, please switch to interface/stlink.cfg
Info : auto-selecting first available session transport "hla_swd". To override use 'transport select <transport>'.
Info : The selected transport took over low-level target control. The results might differ compared to plain JTAG/SWD
Info : Listening on port 6666 for tcl connections
Info : Listening on port 4444 for telnet connections
Info : clock speed 2000 kHz
...
...
[stm32f4x.cpu] halted due to debug-request, current mode: Thread
xPSR: 0x01000000 pc: 0x08009014 msp: 0x2001fff0
Start address 0x08009014, load size 336977
Transfer rate: 37 KB/sec, 11232 bytes/write.
(gdb) c
Continuing.
^C
Program received signal SIGINT, Interrupt.
0x08021a1c in scheduler () at ./src/main/scheduler/scheduler.c:695
695 task->taskAgePeriods = (cmpTimeUs(currentTimeUs, task->lastExecutedAtUs) / task->attribute->desiredPeriodUs);
(gdb) quit
works as expected.
In addition add also G4 and H7 TARGET_MCU_FAMILY support. When installing openocd the config files for G4 and H7, should
be provided in directory: /usr/share/openocd/scripts/target
$ grep -r TARGET_MCU_FAMILY | awk '/ STM32/{print $3}' | sort | uniq && find /usr/share/openocd/scripts/target -type f | grep "stm32f4x.cfg\|stm32f7x.cfg\|stm32g4x.cfg\|stm32h7x.cfg"
STM32F4
STM32F7
STM32G4
STM32H7
/usr/share/openocd/scripts/target/stm32g4x.cfg
/usr/share/openocd/scripts/target/stm32h7x.cfg
/usr/share/openocd/scripts/target/stm32f4x.cfg
/usr/share/openocd/scripts/target/stm32f7x.cfg
* Remove useless else
* Override failsafe when MSP_OVERRIDE active
Fixes#13374
Set `rxSignalReceived = true` If MSP_OVERRIDE is active, so that it can be checked later. Otherwise, MSP controls are not considered in failsafe checks.
* Do override only if BOXMOODEOVERRIDE box is active as well
* Update msp.h
* Update msp.c
* Make sure that failsafe works when there is no signal from MSP
* Introduce rxMspOverrideFrameStatus to make a clear separation from rxMspFrameStatus
* Update src/main/rx/msp.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* add msp_override_failsafe
* Update src/main/pg/rx.h
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Update src/main/rx/rx.c
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
* Log the standard deviation of gyro cycle time in SCHEDULER_DETERMINISM and TIMING_ACCURACY
* Update src/main/scheduler/scheduler.c
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Update src/main/scheduler/scheduler.c
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Use cpu_late_10ths_percent_limit to set limit on % of late tasks in 10th of a %
Set CPU load late limit to 1% based on testing
* Update src/main/cli/settings.c
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Update src/main/scheduler/scheduler.h
Co-authored-by: Jan Post <Rm2k-Freak@web.de>
* Update src/main/fc/core.c
* Update src/test/unit/arming_prevention_unittest.cc
* Update src/main/scheduler/scheduler.c
---------
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
Co-authored-by: Jan Post <Rm2k-Freak@web.de>