1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Merge remote-tracking branch 'upstream/master' into abo_emerg_landing_revamp

This commit is contained in:
breadoven 2021-09-08 13:00:08 +01:00
commit 6c5bfa3a40
119 changed files with 2075 additions and 1878 deletions

View file

@ -2,13 +2,13 @@ include(gcc)
set(arm_none_eabi_triplet "arm-none-eabi")
# Keep version in sync with the distribution files below
set(arm_none_eabi_gcc_version "9.3.1")
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/9-2020q2/gcc-arm-none-eabi-9-2020-q2-update")
set(arm_none_eabi_gcc_version "10.2.1")
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10-2020q4/gcc-arm-none-eabi-10-2020-q4-major")
# suffix and checksum
set(arm_none_eabi_win32 "win32.zip" 184b3397414485f224e7ba950989aab6)
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 2b9eeccc33470f9d3cda26983b9d2dc6)
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 000b0888cbe7b171e2225b29be1c327c)
set(arm_none_eabi_gcc_macos "mac.tar.bz2" 75a171beac35453fd2f0f48b3cb239c3)
set(arm_none_eabi_win32 "win32.zip" 5ee6542a2af847934177bc8fa1294c0d)
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 8312c4c91799885f222f663fc81f9a31)
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 1c3b8944c026d50362eef1f01f329a8e)
set(arm_none_eabi_gcc_macos "mac.tar.bz2" e588d21be5a0cc9caa60938d2422b058)
function(arm_none_eabi_gcc_distname var)
string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url})

View file

@ -19,6 +19,8 @@ main_sources(STM32F3_SRC
target/system_stm32f30x.c
config/config_streamer_stm32f3.c
config/config_streamer_ram.c
config/config_streamer_extflash.c
drivers/adc_stm32f30x.c
drivers/bus_i2c_stm32f30x.c

View file

@ -36,6 +36,8 @@ main_sources(STM32F4_SRC
target/system_stm32f4xx.c
config/config_streamer_stm32f4.c
config/config_streamer_ram.c
config/config_streamer_extflash.c
drivers/adc_stm32f4xx.c
drivers/adc_stm32f4xx.c
@ -124,6 +126,7 @@ exclude_basenames(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F411_OR_F427_STDPERIPH_
set(STM32F411_COMPILE_DEFINITIONS
STM32F411xE
MCU_FLASH_SIZE=512
OPTIMIZATION -Os
)
function(target_stm32f411xe name)
@ -132,9 +135,9 @@ function(target_stm32f411xe name)
STARTUP startup_stm32f411xe.s
SOURCES ${STM32F411_OR_F427_STDPERIPH_SRC}
COMPILE_DEFINITIONS ${STM32F411_COMPILE_DEFINITIONS}
LINKER_SCRIPT stm32_flash_f411xe
LINKER_SCRIPT stm32_flash_f411xe
SVD STM32F411
${ARGN}
${ARGN}
)
endfunction()

View file

@ -61,6 +61,8 @@ main_sources(STM32F7_SRC
target/system_stm32f7xx.c
config/config_streamer_stm32f7.c
config/config_streamer_ram.c
config/config_streamer_extflash.c
drivers/adc_stm32f7xx.c
drivers/bus_i2c_hal.c

View file

@ -142,6 +142,8 @@ main_sources(STM32H7_SRC
target/system_stm32h7xx.c
config/config_streamer_stm32h7.c
config/config_streamer_ram.c
config/config_streamer_extflash.c
drivers/adc_stm32h7xx.c
drivers/bus_i2c_hal.c
@ -217,4 +219,4 @@ macro(define_target_stm32h7 subfamily size)
endfunction()
endmacro()
define_target_stm32h7(43 i)
define_target_stm32h7(43 i)

View file

@ -39,6 +39,7 @@ The stick positions are combined to activate different functions:
| Save setting | LOW | LOW | LOW | HIGH |
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/).
![Stick Positions](assets/images/StickPositions.png)
## Yaw control

View file

@ -1948,7 +1948,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements
| Default | Min | Max |
| --- | --- | --- |
| 2500 | | 65535 |
| 1000 | | 65535 |
---
@ -1958,7 +1958,7 @@ Inertial Measurement Unit KP Gain for compass measurements
| Default | Min | Max |
| --- | --- | --- |
| 10000 | | 65535 |
| 5000 | | 65535 |
---
@ -4542,6 +4542,16 @@ Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD st
---
### osd_stats_page_auto_swap_time
Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0.
| Default | Min | Max |
| --- | --- | --- |
| 3 | 0 | 10 |
---
### osd_telemetry
To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`

View file

@ -121,6 +121,7 @@ The following sensors are transmitted
* **0430** : if `frsky_pitch_roll = ON` set this will be pitch degrees*10
* **0440** : if `frsky_pitch_roll = ON` set this will be roll degrees*10
* **0450** : 'Flight Path Vector' or 'Course over ground' in degrees*10
* **0460** : Azimuth in degrees*10
### Compatible SmartPort/INAV telemetry flight status
To quickly and easily monitor these SmartPort sensors and flight modes, install [OpenTX Telemetry Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.

View file

@ -138,3 +138,18 @@ appendWindowsPath=false
8. `cd build`
9. `cmake ..`
9. `make {TARGET}` should be working again
### Building targets is very slow
I was pretty shocked when my new i7 -10750 laptop took 25 minutes to build a single target. My old i3-4030 could do the same job in about 2.5 minutes. If you're also suffering from slow builds. Open an elevated PowerShell window and type
```
wsl -l -v
```
If you see your Linux distribution is using WSL 2, this is the problem. WSL 2 is quicker than WSL 1 for a lot of things. However, if your files are on a windows mounted drive in Linux, it is extremely slow. There are two options:
1. Put your files on the Linux file system
2. Change to WSL 1
I opted for the latter. To do this, in the elevated PowerShell window, you can see the name of your distro. Mine is **Ubuntu-20.04**, so I'll use that in this example. Simply type
```
wsl --set-version Ubuntu-20.04 1
```
and your distro will be converted to WSL 1. Once finished, reboot your system. Next time you compile a build, it will be faster.

View file

@ -0,0 +1,80 @@
# General Info
This is a guide on how to use Windows MSYS2 distribution and building platform to build iNav firmware. This environment is very simple to manage and does not require installing docker for Windows which may get in the way of VMWare or any other virtualization software you already have running for other reasons. Another benefit of this approach is that the compiler runs natively on Windows, so performance is much better than compiling in a virtual environment or a container. You can also integrate with whatever IDE you are using to make code edits and work with github, which makes the entire development and testing workflow a lot more efficient. In addition to MSYS2, this build environment also uses Arm Embedded GCC tolkit from The xPack Project, which provides many benefits over the toolkits maintained by arm.com
Some of those benefits are described here:
https://xpack.github.io/arm-none-eabi-gcc/
## Setting up build environment
Download MSYS2 for your architecture (most likely 64-bit)
https://www.msys2.org/wiki/MSYS2-installation/
Click on 64-bit, scroll all the way down for the latest release
pacman is the package manager which makes it a lot easier to install and maintain all the dependencies
## Installing dependencies
Once MSYS2 is installed, you can open up a new terminal window by running:
"C:\msys64\mingw64.exe"
You can also make a shortcut of this somewhere on your taskbar, desktop, etc, or even setup a shortcut key to open it up every time you need to get a terminal window. If you right click on the window you can customize the font and layout to make it more comfortable to work with. This is very similar to cygwin or any other terminal program you might have used before
This is the best part:
```
pacman -S git ruby make cmake gcc mingw-w64-x86_64-libwinpthread-git unzip wget
```
Now, each release needs a different version of arm toolchain. To setup the xPack ARM toolchain, use the following process:
First, setup your work path, get the release you want to build or master if you want the latest/greatest
```
mkdir /c/Workspace
cd /c/Workspace
# you can also check out your own fork here which makes contributing easier
git clone https://github.com/iNavFlight/inav
cd inav
# switch to release you want or skip next 2 lines if you want latest
git fetch origin
git checkout -b release_2.6.1 origin/release_2.6.1
```
Now create the build and xpack directories and get the toolkit version you need for your inav version
```
mkdir build
cd build
mkdir /c/Workspace/xpack
cd /c/Workspace/xpack
cat /c/Workspace/inav/cmake/arm-none-eabi-checks.cmake | grep "set(arm_none_eabi_gcc_version" | cut -d\" -f2
```
This will give you the version you need for any given release or master branch. You can get to all the releases here and find the version you need
https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/
```
# for version 2.6.1, version needed is 9.2.1
wget https://github.com/xpack-dev-tools/arm-none-eabi-gcc-xpack/releases/download/v9.2.1-1.1/xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
unzip xpack-arm-none-eabi-gcc-9.2.1-1.1-win32-x64.zip
```
This is important, put the toolkit first before your path so that it is picked up ahead of any other versions that may be present on your system
```
export PATH=/c/Workspace/xpack/xpack-arm-none-eabi-gcc-9.2.1-1.1/bin:$PATH
cd /c/Workspace/inav/build
```
You may need to run rm -rf * in build directory if you had any failed previous runs now run cmake
```
# while inside the build directory
cmake ..
```
Once that's done you can compile the firmware for your controller
```
make DALRCF405
```
To get a list of available targets in iNav, see the target src folder
https://github.com/tednv/inav/tree/master/src/main/target
The generated hex file will be in /c/Workspace/inav/build folder
At the time of writting this document, I believe this is the fastest, easiest, and most efficient Windows build environment that is available. I have used this approach several years ago and was very happy with it building iNav 2.1 and 2.2, and now I'm getting back into it so figured I would share my method

View file

@ -79,6 +79,9 @@ main_sources(COMMON_SRC
drivers/accgyro/accgyro_bmi088.h
drivers/accgyro/accgyro_bmi160.c
drivers/accgyro/accgyro_bmi160.h
drivers/accgyro/accgyro_bmi270.c
drivers/accgyro/accgyro_bmi270.h
drivers/accgyro/accgyro_bmi270_maximum_fifo.c
drivers/accgyro/accgyro_fake.c
drivers/accgyro/accgyro_fake.h
drivers/accgyro/accgyro_icm20689.c
@ -249,8 +252,6 @@ main_sources(COMMON_SRC
drivers/resource.h
drivers/rcc.c
drivers/rcc.h
drivers/rx_pwm.c
drivers/rx_pwm.h
drivers/rx_spi.c
drivers/rx_spi.h
drivers/serial.c
@ -413,8 +414,6 @@ main_sources(COMMON_SRC
rx/msp.h
rx/msp_override.c
rx/msp_override.h
rx/pwm.c
rx/pwm.h
rx/frsky_crc.c
rx/frsky_crc.h
rx/rx.c

View file

@ -97,15 +97,30 @@
#define BLACKBOX_INVERTED_CARD_DETECTION 0
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 2);
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
.device = DEFAULT_BLACKBOX_DEVICE,
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
.includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS | BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE,
);
void blackboxIncludeFlagSet(uint32_t mask)
{
blackboxConfigMutable()->includeFlags |= mask;
}
void blackboxIncludeFlagClear(uint32_t mask)
{
blackboxConfigMutable()->includeFlags &= ~(mask);
}
bool blackboxIncludeFlag(uint32_t mask) {
return (blackboxConfig()->includeFlags & mask) == mask;
}
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
static const int32_t blackboxSInterval = 4096;
@ -199,6 +214,9 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
{"axisD", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)},
{"axisD", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)},
{"axisD", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)},
{"axisF", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ALWAYS},
{"axisF", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ALWAYS},
{"axisF", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ALWAYS},
{"fwAltP", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
{"fwAltI", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
@ -267,12 +285,12 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
{"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"attitude", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"attitude", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"attitude", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
{"attitude", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ATTITUDE},
{"attitude", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ATTITUDE},
{"attitude", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ATTITUDE},
{"debug", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
{"debug", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
{"debug", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
@ -310,28 +328,26 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
{"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
{"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)},
#ifdef NAV_BLACKBOX
{"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navEPH", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navEPV", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navPos", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navPos", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navVel", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navVel", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navVel", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navAcc", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navAcc", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navAcc", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtVel", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtVel", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtVel", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtPos", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtPos", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navTgtPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
{"navSurf", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
#endif
{"navEPH", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navEPV", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navPos", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navPos", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navVel", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navVel", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navVel", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtVel", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtVel", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtVel", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtPos", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtPos", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navTgtPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navSurf", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
{"navAcc", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
{"navAcc", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
{"navAcc", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
};
#ifdef USE_GPS
@ -422,6 +438,7 @@ typedef struct blackboxMainState_s {
int32_t axisPID_P[XYZ_AXIS_COUNT];
int32_t axisPID_I[XYZ_AXIS_COUNT];
int32_t axisPID_D[XYZ_AXIS_COUNT];
int32_t axisPID_F[XYZ_AXIS_COUNT];
int32_t axisPID_Setpoint[XYZ_AXIS_COUNT];
int32_t mcPosAxisP[XYZ_AXIS_COUNT];
@ -461,7 +478,6 @@ typedef struct blackboxMainState_s {
int32_t surfaceRaw;
#endif
uint16_t rssi;
#ifdef NAV_BLACKBOX
int16_t navState;
uint16_t navFlags;
uint16_t navEPH;
@ -474,7 +490,6 @@ typedef struct blackboxMainState_s {
int16_t navHeading;
int16_t navTargetHeading;
int16_t navSurface;
#endif
} blackboxMainState_t;
typedef struct blackboxGpsState_s {
@ -596,11 +611,11 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
// D output can be set by either the D or the FF term
return pidBank()->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0 || pidBank()->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].FF != 0;
return pidBank()->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0;
case FLIGHT_LOG_FIELD_CONDITION_MAG:
#ifdef USE_MAG
return sensors(SENSOR_MAG);
return sensors(SENSOR_MAG) && blackboxIncludeFlag(BLACKBOX_FEATURE_MAG);
#else
return false;
#endif
@ -634,14 +649,14 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV:
#ifdef USE_NAV
return STATE(FIXED_WING_LEGACY);
return STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
#else
return false;
#endif
case FLIGHT_LOG_FIELD_CONDITION_MC_NAV:
#ifdef USE_NAV
return !STATE(FIXED_WING_LEGACY);
return !STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
#else
return false;
#endif
@ -657,9 +672,22 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_DEBUG:
return debugMode != DEBUG_NONE;
case FLIGHT_LOG_FIELD_CONDITION_NAV_ACC:
return blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_ACC);
case FLIGHT_LOG_FIELD_CONDITION_NAV_POS:
return blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_POS);
case FLIGHT_LOG_FIELD_CONDITION_ACC:
return blackboxIncludeFlag(BLACKBOX_FEATURE_ACC);
case FLIGHT_LOG_FIELD_CONDITION_ATTITUDE:
return blackboxIncludeFlag(BLACKBOX_FEATURE_ATTITUDE);
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
return false;
default:
return false;
}
@ -733,6 +761,7 @@ static void writeIntraframe(void)
blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x]);
}
}
blackboxWriteSignedVBArray(blackboxCurrent->axisPID_F, XYZ_AXIS_COUNT);
if (testBlackboxCondition(CONDITION(FIXED_WING_NAV))) {
blackboxWriteSignedVBArray(blackboxCurrent->fwAltPID, 3);
@ -811,8 +840,14 @@ static void writeIntraframe(void)
}
blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
blackboxWriteSigned16VBArray(blackboxCurrent->attitude, XYZ_AXIS_COUNT);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ATTITUDE)) {
blackboxWriteSigned16VBArray(blackboxCurrent->attitude, XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
blackboxWriteSignedVBArray(blackboxCurrent->debug, DEBUG32_VALUE_COUNT);
@ -834,36 +869,41 @@ static void writeIntraframe(void)
}
}
#ifdef NAV_BLACKBOX
blackboxWriteSignedVB(blackboxCurrent->navState);
blackboxWriteSignedVB(blackboxCurrent->navFlags);
blackboxWriteSignedVB(blackboxCurrent->navEPH);
blackboxWriteSignedVB(blackboxCurrent->navEPV);
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navPos[x]);
/*
* NAV_POS fields
*/
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_POS)) {
blackboxWriteSignedVB(blackboxCurrent->navEPH);
blackboxWriteSignedVB(blackboxCurrent->navEPV);
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navPos[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navRealVel[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navTargetVel[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navTargetPos[x]);
}
blackboxWriteSignedVB(blackboxCurrent->navSurface);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navRealVel[x]);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_ACC)) {
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navAccNEU[x]);
}
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navAccNEU[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navTargetVel[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navTargetPos[x]);
}
blackboxWriteSignedVB(blackboxCurrent->navSurface);
#endif
//Rotate our history buffers:
//The current state becomes the new "before" state
@ -943,6 +983,9 @@ static void writeInterframe(void)
}
}
arraySubInt32(deltas, blackboxCurrent->axisPID_F, blackboxLast->axisPID_F, XYZ_AXIS_COUNT);
blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
if (testBlackboxCondition(CONDITION(FIXED_WING_NAV))) {
arraySubInt32(deltas, blackboxCurrent->fwAltPID, blackboxLast->fwAltPID, 3);
@ -1039,8 +1082,15 @@ static void writeInterframe(void)
//Since gyros, accs and motors are noisy, base their predictions on the average of the history:
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, attitude), XYZ_AXIS_COUNT);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ATTITUDE)) {
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, attitude), XYZ_AXIS_COUNT);
}
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
}
@ -1050,36 +1100,43 @@ static void writeInterframe(void)
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
}
#ifdef NAV_BLACKBOX
blackboxWriteSignedVB(blackboxCurrent->navState - blackboxLast->navState);
blackboxWriteSignedVB(blackboxCurrent->navFlags - blackboxLast->navFlags);
blackboxWriteSignedVB(blackboxCurrent->navEPH - blackboxLast->navEPH);
blackboxWriteSignedVB(blackboxCurrent->navEPV - blackboxLast->navEPV);
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navPos[x] - blackboxLast->navPos[x]);
/*
* NAV_POS fields
*/
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_POS)) {
blackboxWriteSignedVB(blackboxCurrent->navEPH - blackboxLast->navEPH);
blackboxWriteSignedVB(blackboxCurrent->navEPV - blackboxLast->navEPV);
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxCurrent->navPos[x] - blackboxLast->navPos[x]);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navRealVel[x] - (blackboxHistory[1]->navRealVel[x] + blackboxHistory[2]->navRealVel[x]) / 2);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navTargetVel[x] - (blackboxHistory[1]->navTargetVel[x] + blackboxHistory[2]->navTargetVel[x]) / 2);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navTargetPos[x] - blackboxLast->navTargetPos[x]);
}
blackboxWriteSignedVB(blackboxCurrent->navSurface - blackboxLast->navSurface);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navRealVel[x] - (blackboxHistory[1]->navRealVel[x] + blackboxHistory[2]->navRealVel[x]) / 2);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_ACC)) {
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navAccNEU[x] - (blackboxHistory[1]->navAccNEU[x] + blackboxHistory[2]->navAccNEU[x]) / 2);
}
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navAccNEU[x] - (blackboxHistory[1]->navAccNEU[x] + blackboxHistory[2]->navAccNEU[x]) / 2);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navTargetVel[x] - (blackboxHistory[1]->navTargetVel[x] + blackboxHistory[2]->navTargetVel[x]) / 2);
}
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
blackboxWriteSignedVB(blackboxHistory[0]->navTargetPos[x] - blackboxLast->navTargetPos[x]);
}
blackboxWriteSignedVB(blackboxCurrent->navSurface - blackboxLast->navSurface);
#endif
//Rotate our history buffers
blackboxHistory[2] = blackboxHistory[1];
blackboxHistory[1] = blackboxHistory[0];
@ -1396,6 +1453,7 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->axisPID_P[i] = axisPID_P[i];
blackboxCurrent->axisPID_I[i] = axisPID_I[i];
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
blackboxCurrent->axisPID_F[i] = axisPID_F[i];
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
#ifdef USE_MAG
@ -1479,7 +1537,6 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->servo[i] = servo[i];
}
#ifdef NAV_BLACKBOX
blackboxCurrent->navState = navCurrentState;
blackboxCurrent->navFlags = navFlags;
blackboxCurrent->navEPH = navEPH;
@ -1492,7 +1549,6 @@ static void loadMainState(timeUs_t currentTimeUs)
blackboxCurrent->navTargetPos[i] = navTargetPosition[i];
}
blackboxCurrent->navSurface = navActualSurface;
#endif
}
/**
@ -1690,15 +1746,18 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->stabilized.rates[ROLL],
currentControlRateProfile->stabilized.rates[PITCH],
currentControlRateProfile->stabilized.rates[YAW]);
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", pidBank()->pid[PID_ROLL].P,
BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d,%d", pidBank()->pid[PID_ROLL].P,
pidBank()->pid[PID_ROLL].I,
pidBank()->pid[PID_ROLL].D);
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", pidBank()->pid[PID_PITCH].P,
pidBank()->pid[PID_ROLL].D,
pidBank()->pid[PID_ROLL].FF);
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d,%d", pidBank()->pid[PID_PITCH].P,
pidBank()->pid[PID_PITCH].I,
pidBank()->pid[PID_PITCH].D);
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", pidBank()->pid[PID_YAW].P,
pidBank()->pid[PID_PITCH].D,
pidBank()->pid[PID_PITCH].FF);
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d,%d", pidBank()->pid[PID_YAW].P,
pidBank()->pid[PID_YAW].I,
pidBank()->pid[PID_YAW].D);
pidBank()->pid[PID_YAW].D,
pidBank()->pid[PID_YAW].FF);
BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", pidBank()->pid[PID_POS_Z].P,
pidBank()->pid[PID_POS_Z].I,
pidBank()->pid[PID_POS_Z].D);
@ -1749,9 +1808,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->motorPwmRate);
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
#ifdef NAV_BLACKBOX
BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid());
#endif
BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);

View file

@ -21,11 +21,22 @@
#include "config/parameter_group.h"
typedef enum {
BLACKBOX_FEATURE_NAV_ACC = 1 << 0,
BLACKBOX_FEATURE_NAV_POS = 1 << 1,
BLACKBOX_FEATURE_NAV_PID = 1 << 2,
BLACKBOX_FEATURE_MAG = 1 << 3,
BLACKBOX_FEATURE_ACC = 1 << 4,
BLACKBOX_FEATURE_ATTITUDE = 1 << 5,
} blackboxFeatureMask_e;
typedef struct blackboxConfig_s {
uint16_t rate_num;
uint16_t rate_denom;
uint8_t device;
uint8_t invertedCardDetection;
uint32_t includeFlags;
} blackboxConfig_t;
PG_DECLARE(blackboxConfig_t, blackboxConfig);
@ -37,3 +48,6 @@ void blackboxUpdate(timeUs_t currentTimeUs);
void blackboxStart(void);
void blackboxFinish(void);
bool blackboxMayEditConfig(void);
void blackboxIncludeFlagSet(uint32_t mask);
void blackboxIncludeFlagClear(uint32_t mask);
bool blackboxIncludeFlag(uint32_t mask);

View file

@ -52,6 +52,12 @@ typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_DEBUG,
FLIGHT_LOG_FIELD_CONDITION_NAV_ACC,
FLIGHT_LOG_FIELD_CONDITION_NAV_POS,
FLIGHT_LOG_FIELD_CONDITION_NAV_PID,
FLIGHT_LOG_FIELD_CONDITION_ACC,
FLIGHT_LOG_FIELD_CONDITION_ATTITUDE,
FLIGHT_LOG_FIELD_CONDITION_NEVER,
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,

View file

@ -53,8 +53,10 @@
#ifdef STM32H7
#define DMA_RAM __attribute__ ((section(".DMA_RAM")))
#define SLOW_RAM __attribute__ ((section(".SLOW_RAM")))
#else
#define DMA_RAM
#define SLOW_RAM
#endif
#define STATIC_FASTRAM static FASTRAM

View file

@ -72,7 +72,6 @@ typedef enum {
DEBUG_DYNAMIC_FILTER,
DEBUG_DYNAMIC_FILTER_FREQUENCY,
DEBUG_IRLOCK,
DEBUG_CD,
DEBUG_KALMAN_GAIN,
DEBUG_PID_MEASUREMENT,
DEBUG_SPM_CELLS, // Smartport master FLVSS
@ -81,7 +80,6 @@ typedef enum {
DEBUG_PCF8574,
DEBUG_DYNAMIC_GYRO_LPF,
DEBUG_AUTOLEVEL,
DEBUG_FW_D,
DEBUG_IMU2,
DEBUG_ALTITUDE,
DEBUG_GYRO_ALPHA_BETA_GAMMA,

View file

@ -43,12 +43,16 @@ static const OSD_Entry menuMiscEntries[]=
OSD_LABEL_ENTRY("-- MISC --"),
OSD_SETTING_ENTRY("THR IDLE", SETTING_THROTTLE_IDLE),
#if defined(USE_OSD) && defined(USE_ADC)
#ifdef USE_OSD
#ifdef USE_ADC
OSD_SETTING_ENTRY("OSD VOLT DECIMALS", SETTING_OSD_MAIN_VOLTAGE_DECIMALS),
OSD_SETTING_ENTRY("STATS ENERGY UNIT", SETTING_OSD_STATS_ENERGY_UNIT),
#endif
#endif // ADC
OSD_SETTING_ENTRY("STATS PAGE SWAP TIME", SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME),
#endif // OSD
OSD_SETTING_ENTRY("FS PROCEDURE", SETTING_FAILSAFE_PROCEDURE),
OSD_BACK_AND_END_ENTRY,
};

View file

@ -18,7 +18,8 @@
#pragma once
#define FEET_PER_MILE 5280
#define FEET_PER_NAUTICALMILE 6076.118
#define FEET_PER_KILOFEET 1000 // Used for altitude
#define METERS_PER_KILOMETER 1000
#define METERS_PER_MILE 1609
#define METERS_PER_MILE 1609.344
#define METERS_PER_NAUTICALMILE 1852.001

View file

@ -56,12 +56,16 @@
#define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD)
#define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD)
#define CENTIMETERS_TO_CENTIFEET(cm) (cm * (328 / 100.0))
#define CENTIMETERS_TO_FEET(cm) (cm * (328 / 10000.0))
#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048)
#define CENTIMETERS_TO_FEET(cm) (cm / 30.48)
#define CENTIMETERS_TO_METERS(cm) (cm / 100)
#define METERS_TO_CENTIMETERS(m) (m * 100)
#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363)
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6)
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845)
// copied from https://code.google.com/p/cxutil/source/browse/include/cxutil/utility.h#70
#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \
( __extension__ ({ \

View file

@ -25,12 +25,14 @@
#include "build/build_config.h"
#include "common/crc.h"
#include "common/utils.h"
#include "config/config_eeprom.h"
#include "config/config_streamer.h"
#include "config/parameter_group.h"
#include "drivers/system.h"
#include "drivers/flash.h"
#include "fc/config.h"
@ -76,6 +78,31 @@ typedef struct {
uint32_t word;
} PG_PACKED packingTest_t;
#if defined(CONFIG_IN_EXTERNAL_FLASH)
bool loadEEPROMFromExternalFlash(void)
{
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG);
const flashGeometry_t *flashGeometry = flashGetGeometry();
uint32_t flashStartAddress = flashPartition->startSector * flashGeometry->sectorSize;
uint32_t totalBytesRead = 0;
int bytesRead = 0;
bool success = false;
do {
bytesRead = flashReadBytes(flashStartAddress + totalBytesRead, &eepromData[totalBytesRead], EEPROM_SIZE - totalBytesRead);
if (bytesRead > 0) {
totalBytesRead += bytesRead;
success = (totalBytesRead == EEPROM_SIZE);
}
} while (!success && bytesRead > 0);
return success;
}
#endif /* defined(CONFIG_IN_EXTERNAL_FLASH) */
void initEEPROM(void)
{
// Verify that this architecture packs as expected.
@ -86,6 +113,14 @@ void initEEPROM(void)
BUILD_BUG_ON(sizeof(configHeader_t) != 1);
BUILD_BUG_ON(sizeof(configFooter_t) != 2);
BUILD_BUG_ON(sizeof(configRecord_t) != 6);
#if defined(CONFIG_IN_EXTERNAL_FLASH)
bool eepromLoaded = loadEEPROMFromExternalFlash();
if (!eepromLoaded) {
// Flash read failed - just die now
failureMode(FAILURE_FLASH_READ_FAILED);
}
#endif
}
static uint16_t updateCRC(uint16_t crc, const void *data, uint32_t length)
@ -217,7 +252,9 @@ static bool writeSettingsToEEPROM(void)
.format = EEPROM_CONF_VERSION,
};
config_streamer_write(&streamer, (uint8_t *)&header, sizeof(header));
if (config_streamer_write(&streamer, (uint8_t *)&header, sizeof(header)) < 0) {
return false;
}
uint16_t crc = updateCRC(0, (uint8_t *)&header, sizeof(header));
PG_FOREACH(reg) {
const uint16_t regSize = pgSize(reg);
@ -231,9 +268,13 @@ static bool writeSettingsToEEPROM(void)
if (pgIsSystem(reg)) {
// write the only instance
record.flags |= CR_CLASSICATION_SYSTEM;
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
if (config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record)) < 0) {
return false;
}
crc = updateCRC(crc, (uint8_t *)&record, sizeof(record));
config_streamer_write(&streamer, reg->address, regSize);
if (config_streamer_write(&streamer, reg->address, regSize) < 0) {
return false;
}
crc = updateCRC(crc, reg->address, regSize);
} else {
// write one instance for each profile
@ -241,10 +282,14 @@ static bool writeSettingsToEEPROM(void)
record.flags = 0;
record.flags |= ((profileIndex + 1) & CR_CLASSIFICATION_MASK);
config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record));
if (config_streamer_write(&streamer, (uint8_t *)&record, sizeof(record)) < 0) {
return false;
}
crc = updateCRC(crc, (uint8_t *)&record, sizeof(record));
const uint8_t *address = reg->address + (regSize * profileIndex);
config_streamer_write(&streamer, address, regSize);
if (config_streamer_write(&streamer, address, regSize) < 0) {
return false;
}
crc = updateCRC(crc, address, regSize);
}
}
@ -254,13 +299,19 @@ static bool writeSettingsToEEPROM(void)
.terminator = 0,
};
config_streamer_write(&streamer, (uint8_t *)&footer, sizeof(footer));
if (config_streamer_write(&streamer, (uint8_t *)&footer, sizeof(footer)) < 0) {
return false;
}
crc = updateCRC(crc, (uint8_t *)&footer, sizeof(footer));
// append checksum now
config_streamer_write(&streamer, (uint8_t *)&crc, sizeof(crc));
if (config_streamer_write(&streamer, (uint8_t *)&crc, sizeof(crc)) < 0) {
return false;
}
config_streamer_flush(&streamer);
if (config_streamer_flush(&streamer) < 0) {
return false;
}
bool success = config_streamer_finish(&streamer) == 0;
@ -274,6 +325,10 @@ void writeConfigToEEPROM(void)
for (int attempt = 0; attempt < 3 && !success; attempt++) {
if (writeSettingsToEEPROM()) {
success = true;
#ifdef CONFIG_IN_EXTERNAL_FLASH
// copy it back from flash to the in-memory buffer.
success = loadEEPROMFromExternalFlash();
#endif
}
}

View file

@ -24,8 +24,6 @@
#include "common/axis.h"
#include "common/color.h"
#include "drivers/rx_pwm.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "flight/servos.h"

View file

@ -19,6 +19,11 @@
#include "platform.h"
#include "drivers/system.h"
#include "config/config_streamer.h"
#include "build/build_config.h"
#if !defined(CONFIG_IN_FLASH)
SLOW_RAM uint8_t eepromData[EEPROM_SIZE];
#endif
// Helper functions
extern void config_streamer_impl_unlock(void);
@ -35,6 +40,7 @@ void config_streamer_start(config_streamer_t *c, uintptr_t base, int size)
// base must start at FLASH_PAGE_SIZE boundary when using embedded flash.
c->address = base;
c->size = size;
c->end = base + size;
if (!c->unlocked) {
config_streamer_impl_unlock();
c->unlocked = true;
@ -44,6 +50,11 @@ void config_streamer_start(config_streamer_t *c, uintptr_t base, int size)
int config_streamer_write(config_streamer_t *c, const uint8_t *p, uint32_t size)
{
if ((c->address + size) > c->end) {
// trying to write past end of streamer
return -1;
}
for (const uint8_t *pat = p; pat != (uint8_t*)p + size; pat++) {
c->buffer.b[c->at++] = *pat;
@ -63,6 +74,9 @@ int config_streamer_status(config_streamer_t *c)
int config_streamer_flush(config_streamer_t *c)
{
if (c->at != 0) {
if ((c->address + c->at) > c->end) {
return -1;
}
memset(c->buffer.b + c->at, 0, sizeof(c->buffer) - c->at);
c->err = config_streamer_impl_write_word(c, &c->buffer.w);
c->at = 0;

View file

@ -20,10 +20,15 @@
#include <stdint.h>
#include <stdbool.h>
#include "drivers/flash_m25p16.h"
// Streams data out to the EEPROM, padding to the write size as
// needed, and updating the checksum as it goes.
#if defined(STM32H7)
#ifdef CONFIG_IN_EXTERNAL_FLASH
#define CONFIG_STREAMER_BUFFER_SIZE M25P16_PAGESIZE // Must match flash device page size
typedef uint32_t config_streamer_buffer_align_type_t;
#elif defined(STM32H7)
#define CONFIG_STREAMER_BUFFER_SIZE 32 // Flash word = 256-bits
typedef uint64_t config_streamer_buffer_align_type_t;
#else
@ -33,6 +38,7 @@ typedef uint32_t config_streamer_buffer_align_type_t;
typedef struct config_streamer_s {
uintptr_t address;
uintptr_t end;
int size;
union {
uint8_t b[CONFIG_STREAMER_BUFFER_SIZE];

View file

@ -0,0 +1,77 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include "platform.h"
#include "drivers/system.h"
#include "drivers/flash.h"
#include "config/config_streamer.h"
#if defined(CONFIG_IN_EXTERNAL_FLASH)
static bool streamerLocked = true;
void config_streamer_impl_unlock(void)
{
const flashGeometry_t *flashGeometry = flashGetGeometry();
if (flashGeometry->pageSize == CONFIG_STREAMER_BUFFER_SIZE) {
// streamer needs to buffer exactly one flash page
streamerLocked = false;
}
}
void config_streamer_impl_lock(void)
{
streamerLocked = true;
}
int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer_align_type_t *buffer)
{
if (streamerLocked) {
return -1;
}
uint32_t dataOffset = (uint32_t)(c->address - (uintptr_t)&eepromData[0]);
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG);
const flashGeometry_t *flashGeometry = flashGetGeometry();
uint32_t flashStartAddress = flashPartition->startSector * flashGeometry->sectorSize;
uint32_t flashOverflowAddress = ((flashPartition->endSector + 1) * flashGeometry->sectorSize); // +1 to sector for inclusive
uint32_t flashAddress = flashStartAddress + dataOffset;
if (flashAddress + CONFIG_STREAMER_BUFFER_SIZE > flashOverflowAddress) {
return -2; // address is past end of partition
}
uint32_t flashSectorSize = flashGeometry->sectorSize;
if (flashAddress % flashSectorSize == 0) {
flashEraseSector(flashAddress);
}
if (flashPageProgram(flashAddress, (uint8_t *)buffer, CONFIG_STREAMER_BUFFER_SIZE) == flashAddress) {
// returned same address: programming failed
return -3;
}
c->address += CONFIG_STREAMER_BUFFER_SIZE;
return 0;
}
#endif

View file

@ -0,0 +1,61 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include "platform.h"
#include "drivers/system.h"
#include "config/config_streamer.h"
#if defined(CONFIG_IN_RAM)
static bool streamerLocked = true;
void config_streamer_impl_unlock(void)
{
streamerLocked = false;
}
void config_streamer_impl_lock(void)
{
streamerLocked = true;
}
int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer_align_type_t *buffer)
{
if (streamerLocked) {
return -1;
}
if (c->address == (uintptr_t)&eepromData[0]) {
memset(eepromData, 0, sizeof(eepromData));
}
config_streamer_buffer_align_type_t *destAddr = (config_streamer_buffer_align_type_t *)c->address;
config_streamer_buffer_align_type_t *srcAddr = buffer;
uint8_t nRows = CONFIG_STREAMER_BUFFER_SIZE / sizeof(config_streamer_buffer_align_type_t);
do {
*destAddr++ = *srcAddr++;
} while(--nRows != 0);
c->address += CONFIG_STREAMER_BUFFER_SIZE;
return 0;
}
#endif

View file

@ -20,7 +20,7 @@
#include "drivers/system.h"
#include "config/config_streamer.h"
#if defined(STM32F3)
#if defined(STM32F3) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH)
#define FLASH_PAGE_SIZE 0x800
@ -57,4 +57,4 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
return 0;
}
#endif
#endif

View file

@ -20,7 +20,7 @@
#include "drivers/system.h"
#include "config/config_streamer.h"
#if defined(STM32F4)
#if defined(STM32F4) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH)
/*
Sector 0 0x08000000 - 0x08003FFF 16 Kbytes
@ -103,4 +103,4 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
return 0;
}
#endif
#endif

View file

@ -20,7 +20,7 @@
#include "drivers/system.h"
#include "config/config_streamer.h"
#if defined(STM32F7)
#if defined(STM32F7) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH)
#if defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx)
/*
@ -138,4 +138,4 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
return 0;
}
#endif
#endif

View file

@ -20,7 +20,7 @@
#include "drivers/system.h"
#include "config/config_streamer.h"
#if defined(STM32H7)
#if defined(STM32H7) && !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_EXTERNAL_FLASH)
#if defined(STM32H743xx)
/* Sectors 0-7 of 128K each */
@ -96,4 +96,4 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer
return 0;
}
#endif
#endif

View file

@ -0,0 +1,338 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#if defined(USE_IMU_BMI270)
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/utils.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h"
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_bmi270.h"
#define BMI270_CONFIG_SIZE 328
// Declaration for the device config (microcode) that must be uploaded to the sensor
extern const uint8_t bmi270_maximum_fifo_config_file[BMI270_CONFIG_SIZE];
// BMI270 registers (not the complete list)
typedef enum {
BMI270_REG_CHIP_ID = 0x00,
BMI270_REG_ERR_REG = 0x02,
BMI270_REG_STATUS = 0x03,
BMI270_REG_ACC_DATA_X_LSB = 0x0C,
BMI270_REG_GYR_DATA_X_LSB = 0x12,
BMI270_REG_SENSORTIME_0 = 0x18,
BMI270_REG_SENSORTIME_1 = 0x19,
BMI270_REG_SENSORTIME_2 = 0x1A,
BMI270_REG_EVENT = 0x1B,
BMI270_REG_INT_STATUS_0 = 0x1C,
BMI270_REG_INT_STATUS_1 = 0x1D,
BMI270_REG_INTERNAL_STATUS = 0x21,
BMI270_REG_TEMPERATURE_LSB = 0x22,
BMI270_REG_TEMPERATURE_MSB = 0x23,
BMI270_REG_FIFO_LENGTH_LSB = 0x24,
BMI270_REG_FIFO_LENGTH_MSB = 0x25,
BMI270_REG_FIFO_DATA = 0x26,
BMI270_REG_ACC_CONF = 0x40,
BMI270_REG_ACC_RANGE = 0x41,
BMI270_REG_GYRO_CONF = 0x42,
BMI270_REG_GYRO_RANGE = 0x43,
BMI270_REG_AUX_CONF = 0x44,
BMI270_REG_FIFO_DOWNS = 0x45,
BMI270_REG_FIFO_WTM_0 = 0x46,
BMI270_REG_FIFO_WTM_1 = 0x47,
BMI270_REG_FIFO_CONFIG_0 = 0x48,
BMI270_REG_FIFO_CONFIG_1 = 0x49,
BMI270_REG_SATURATION = 0x4A,
BMI270_REG_INT1_IO_CTRL = 0x53,
BMI270_REG_INT2_IO_CTRL = 0x54,
BMI270_REG_INT_LATCH = 0x55,
BMI270_REG_INT1_MAP_FEAT = 0x56,
BMI270_REG_INT2_MAP_FEAT = 0x57,
BMI270_REG_INT_MAP_DATA = 0x58,
BMI270_REG_INIT_CTRL = 0x59,
BMI270_REG_INIT_DATA = 0x5E,
BMI270_REG_ACC_SELF_TEST = 0x6D,
BMI270_REG_GYR_SELF_TEST_AXES = 0x6E,
BMI270_REG_PWR_CONF = 0x7C,
BMI270_REG_PWR_CTRL = 0x7D,
BMI270_REG_CMD = 0x7E,
} bmi270Register_e;
#define BMI270_CHIP_ID 0x24
#define BMI270_CMD_SOFTRESET 0xB6
#define BMI270_PWR_CONF_HP 0x00
#define BMI270_PWR_CTRL_GYR_EN 0x02
#define BMI270_PWR_CTRL_ACC_EN 0x04
#define BMI270_PWR_CTRL_TEMP_EN 0x08
#define BMI270_ACC_CONF_HP 0x80
#define BMI270_ACC_RANGE_8G 0x02
#define BMI270_ACC_RANGE_16G 0x03
#define BMI270_GYRO_CONF_NOISE_PERF 0x40
#define BMI270_GYRO_CONF_FILTER_PERF 0x80
#define BMI270_GYRO_RANGE_2000DPS 0x08
#define BMI270_INT_MAP_DATA_DRDY_INT1 0x04
#define BMI270_INT1_IO_CTRL_ACTIVE_HIGH 0x02
#define BMI270_INT1_IO_CTRL_OUTPUT_EN 0x08
#define BMI270_ODR_400 0x0A
#define BMI270_ODR_800 0x0B
#define BMI270_ODR_1600 0x0C
#define BMI270_ODR_3200 0x0D
#define BMI270_BWP_OSR4 0x00
#define BMI270_BWP_OSR2 0x10
#define BMI270_BWP_NORM 0x20
typedef struct __attribute__ ((__packed__)) bmi270ContextData_s {
uint16_t chipMagicNumber;
uint8_t lastReadStatus;
uint8_t __padding_dummy;
uint8_t accRaw[6];
uint8_t gyroRaw[6];
} bmi270ContextData_t;
STATIC_ASSERT(sizeof(bmi270ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small);
static const gyroFilterAndRateConfig_t gyroConfigs[] = {
{ GYRO_LPF_256HZ, 3200, { BMI270_BWP_NORM | BMI270_ODR_3200} },
{ GYRO_LPF_256HZ, 1600, { BMI270_BWP_NORM | BMI270_ODR_1600} },
{ GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } },
{ GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } },
{ GYRO_LPF_188HZ, 400, { BMI270_BWP_NORM | BMI270_ODR_400 } },
{ GYRO_LPF_98HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } },
{ GYRO_LPF_98HZ, 400, { BMI270_BWP_OSR2 | BMI270_ODR_400 } },
{ GYRO_LPF_42HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } },
{ GYRO_LPF_42HZ, 400, { BMI270_BWP_OSR4 | BMI270_ODR_400 } },
};
// Toggle the CS to switch the device into SPI mode.
// Device switches initializes as I2C and switches to SPI on a low to high CS transition
static void bmi270EnableSPI(busDevice_t *dev)
{
IOLo(dev->busdev.spi.csnPin);
delay(1);
IOHi(dev->busdev.spi.csnPin);
delay(10);
}
static bool bmi270DeviceDetect(busDevice_t * busDev)
{
uint8_t id[2];
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
bmi270EnableSPI(busDev);
busReadBuf(busDev, BMI270_REG_CHIP_ID, &id[0], 2);
if (id[1] == BMI270_CHIP_ID) {
return true;
}
return false;
}
static void bmi270UploadConfig(busDevice_t * busDev)
{
busWrite(busDev, BMI270_REG_PWR_CONF, 0);
delay(1);
busWrite(busDev, BMI270_REG_INIT_CTRL, 0);
delay(1);
// Transfer the config file
uint8_t reg = BMI270_REG_INIT_DATA;
busTransferDescriptor_t tfDesc[] = {
{.rxBuf = NULL, .txBuf=&reg, .length=1},
{.rxBuf = NULL, .txBuf=(uint8_t *)bmi270_maximum_fifo_config_file, .length=sizeof(bmi270_maximum_fifo_config_file)}
};
spiBusTransferMultiple(busDev, tfDesc, 2);
delay(10);
busWrite(busDev, BMI270_REG_INIT_CTRL, 1);
delay(1);
}
static void bmi270AccAndGyroInit(gyroDev_t *gyro)
{
busDevice_t * busDev = gyro->busDev;
gyroIntExtiInit(gyro);
// Perform a soft reset to set all configuration to default
// Delay 100ms before continuing configuration
busWrite(busDev, BMI270_REG_CMD, BMI270_CMD_SOFTRESET);
delay(100);
// Use standard bus speed
busSetSpeed(busDev, BUS_SPEED_STANDARD);
// Toggle the chip into SPI mode
bmi270EnableSPI(busDev);
bmi270UploadConfig(busDev);
// Configure the accelerometer
busWrite(busDev, BMI270_REG_ACC_CONF, BMI270_ODR_1600 | BMI270_BWP_OSR4 | BMI270_ACC_CONF_HP);
delay(1);
// Configure the accelerometer full-scale range
busWrite(busDev, BMI270_REG_ACC_RANGE, BMI270_ACC_RANGE_8G);
delay(1);
// Configure the gyro
// Figure out suitable filter configuration
const gyroFilterAndRateConfig_t * config = chooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs, &gyroConfigs[0], ARRAYLEN(gyroConfigs));
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
busWrite(busDev, BMI270_REG_GYRO_CONF, config->gyroConfigValues[0] | BMI270_GYRO_CONF_NOISE_PERF | BMI270_GYRO_CONF_FILTER_PERF);
delay(1);
// Configure the gyro full-range scale
busWrite(busDev, BMI270_REG_GYRO_RANGE, BMI270_GYRO_RANGE_2000DPS);
delay(1);
// Configure the gyro data ready interrupt
#ifdef USE_MPU_DATA_READY_SIGNAL
busWrite(busDev, BMI270_REG_INT_MAP_DATA, BMI270_INT_MAP_DATA_DRDY_INT1);
delay(1);
#endif
// Configure the behavior of the INT1 pin
busWrite(busDev, BMI270_REG_INT1_IO_CTRL, BMI270_INT1_IO_CTRL_ACTIVE_HIGH | BMI270_INT1_IO_CTRL_OUTPUT_EN);
delay(1);
// Configure the device for performance mode
busWrite(busDev, BMI270_REG_PWR_CONF, BMI270_PWR_CONF_HP);
delay(1);
// Enable the gyro and accelerometer
busWrite(busDev, BMI270_REG_PWR_CTRL, BMI270_PWR_CTRL_GYR_EN | BMI270_PWR_CTRL_ACC_EN);
delay(1);
}
static bool bmi270yroReadScratchpad(gyroDev_t *gyro)
{
bmi270ContextData_t * ctx = busDeviceGetScratchpadMemory(gyro->busDev);
ctx->lastReadStatus = busReadBuf(gyro->busDev, BMI270_REG_ACC_DATA_X_LSB, &ctx->__padding_dummy, 6 + 6 + 1);
if (ctx->lastReadStatus) {
gyro->gyroADCRaw[X] = (int16_t)((ctx->gyroRaw[1] << 8) | ctx->gyroRaw[0]);
gyro->gyroADCRaw[Y] = (int16_t)((ctx->gyroRaw[3] << 8) | ctx->gyroRaw[2]);
gyro->gyroADCRaw[Z] = (int16_t)((ctx->gyroRaw[5] << 8) | ctx->gyroRaw[4]);
return true;
}
return false;
}
static bool bmi270AccReadScratchpad(accDev_t *acc)
{
bmi270ContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev);
if (ctx->lastReadStatus) {
acc->ADCRaw[X] = (int16_t)((ctx->accRaw[1] << 8) | ctx->accRaw[0]);
acc->ADCRaw[Y] = (int16_t)((ctx->accRaw[3] << 8) | ctx->accRaw[2]);
acc->ADCRaw[Z] = (int16_t)((ctx->accRaw[5] << 8) | ctx->accRaw[4]);
return true;
}
return false;
}
static void bmi270GyroInit(gyroDev_t *gyro)
{
bmi270AccAndGyroInit(gyro);
}
static void bmi270AccInit(accDev_t *acc)
{
// sensor is configured during gyro init
acc->acc_1G = 4096; // 8G sensor scale
}
bool bmi270AccDetect(accDev_t *acc)
{
acc->busDev = busDeviceOpen(BUSTYPE_SPI, DEVHW_BMI270, acc->imuSensorToUse);
if (acc->busDev == NULL) {
return false;
}
bmi270ContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev);
if (ctx->chipMagicNumber != 0xB270) {
return false;
}
acc->initFn = bmi270AccInit;
acc->readFn = bmi270AccReadScratchpad;
return true;
}
bool bmi270GyroDetect(gyroDev_t *gyro)
{
gyro->busDev = busDeviceInit(BUSTYPE_SPI, DEVHW_BMI270, gyro->imuSensorToUse, OWNER_MPU);
if (gyro->busDev == NULL) {
return false;
}
if (!bmi270DeviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev);
return false;
}
// Magic number for ACC detection to indicate that we have detected BMI270 gyro
bmi270ContextData_t * ctx = busDeviceGetScratchpadMemory(gyro->busDev);
ctx->chipMagicNumber = 0xB270;
gyro->initFn = bmi270GyroInit;
gyro->readFn = bmi270yroReadScratchpad;
gyro->intStatusFn = gyroCheckDataReady;
gyro->scale = 1.0f / 16.4f; // 2000 dps
return true;
}
#endif // USE_IMU_BMI270

View file

@ -0,0 +1,26 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/bus.h"
bool bmi270AccDetect(accDev_t *acc);
bool bmi270GyroDetect(gyroDev_t *gyro);

View file

@ -0,0 +1,213 @@
/**
* Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
*
* BSD-3-Clause
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* @file bmi270_maximum_fifo.c
* @date 2020-11-04
* @version v2.63.1
*
*/
/***************************************************************************/
/*! Header files
****************************************************************************/
//#include "bmi270_maximum_fifo.h"
#include "platform.h"
/***************************************************************************/
/*! Global Variable
****************************************************************************/
/*! @name Global array that stores the configuration file of BMI270 */
const uint8_t bmi270_maximum_fifo_config_file[] = {
0xc8, 0x2e, 0x00, 0x2e, 0x80, 0x2e, 0x1a, 0x00, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00,
0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0x90, 0x32, 0x21, 0x2e, 0x59, 0xf5,
0x10, 0x30, 0x21, 0x2e, 0x6a, 0xf5, 0x1a, 0x24, 0x22, 0x00, 0x80, 0x2e, 0x3b, 0x00, 0xc8, 0x2e, 0x44, 0x47, 0x22,
0x00, 0x37, 0x00, 0xa4, 0x00, 0xff, 0x0f, 0xd1, 0x00, 0x07, 0xad, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1,
0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00,
0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x11, 0x24, 0xfc, 0xf5, 0x80, 0x30, 0x40, 0x42, 0x50, 0x50, 0x00, 0x30, 0x12, 0x24, 0xeb,
0x00, 0x03, 0x30, 0x00, 0x2e, 0xc1, 0x86, 0x5a, 0x0e, 0xfb, 0x2f, 0x21, 0x2e, 0xfc, 0xf5, 0x13, 0x24, 0x63, 0xf5,
0xe0, 0x3c, 0x48, 0x00, 0x22, 0x30, 0xf7, 0x80, 0xc2, 0x42, 0xe1, 0x7f, 0x3a, 0x25, 0xfc, 0x86, 0xf0, 0x7f, 0x41,
0x33, 0x98, 0x2e, 0xc2, 0xc4, 0xd6, 0x6f, 0xf1, 0x30, 0xf1, 0x08, 0xc4, 0x6f, 0x11, 0x24, 0xff, 0x03, 0x12, 0x24,
0x00, 0xfc, 0x61, 0x09, 0xa2, 0x08, 0x36, 0xbe, 0x2a, 0xb9, 0x13, 0x24, 0x38, 0x00, 0x64, 0xbb, 0xd1, 0xbe, 0x94,
0x0a, 0x71, 0x08, 0xd5, 0x42, 0x21, 0xbd, 0x91, 0xbc, 0xd2, 0x42, 0xc1, 0x42, 0x00, 0xb2, 0xfe, 0x82, 0x05, 0x2f,
0x50, 0x30, 0x21, 0x2e, 0x21, 0xf2, 0x00, 0x2e, 0x00, 0x2e, 0xd0, 0x2e, 0xf0, 0x6f, 0x02, 0x30, 0x02, 0x42, 0x20,
0x26, 0xe0, 0x6f, 0x02, 0x31, 0x03, 0x40, 0x9a, 0x0a, 0x02, 0x42, 0xf0, 0x37, 0x05, 0x2e, 0x5e, 0xf7, 0x10, 0x08,
0x12, 0x24, 0x1e, 0xf2, 0x80, 0x42, 0x83, 0x84, 0xf1, 0x7f, 0x0a, 0x25, 0x13, 0x30, 0x83, 0x42, 0x3b, 0x82, 0xf0,
0x6f, 0x00, 0x2e, 0x00, 0x2e, 0xd0, 0x2e, 0x12, 0x40, 0x52, 0x42, 0x00, 0x2e, 0x12, 0x40, 0x52, 0x42, 0x3e, 0x84,
0x00, 0x40, 0x40, 0x42, 0x7e, 0x82, 0xe1, 0x7f, 0xf2, 0x7f, 0x98, 0x2e, 0x6a, 0xd6, 0x21, 0x30, 0x23, 0x2e, 0x61,
0xf5, 0xeb, 0x2c, 0xe1, 0x6f
};
// The rest of this is not needed, avoid compiler errors due to pedantic settings
#if false
/*! @name Global array that stores the feature input configuration of BMI270 */
const struct bmi2_feature_config bmi270_maximum_fifo_feat_in[BMI270_MAXIMUM_FIFO_MAX_FEAT_IN] = {
};
/*! @name Global array that stores the feature output configuration */
const struct bmi2_feature_config bmi270_maximum_fifo_feat_out[BMI270_MAXIMUM_FIFO_MAX_FEAT_OUT] = {
};
/******************************************************************************/
/*! Local Function Prototypes
******************************************************************************/
/*!
* @brief This internal API is used to validate the device pointer for
* null conditions.
*
* @param[in] dev : Structure instance of bmi2_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval < 0 -> Fail
*/
static int8_t null_ptr_check(const struct bmi2_dev *dev);
/***************************************************************************/
/*! User Interface Definitions
****************************************************************************/
/*!
* @brief This API:
* 1) updates the device structure with address of the configuration file.
* 2) Initializes BMI270 sensor.
* 3) Writes the configuration file.
* 4) Updates the feature offset parameters in the device structure.
* 5) Updates the maximum number of pages, in the device structure.
*/
int8_t bmi270_maximum_fifo_init(struct bmi2_dev *dev)
{
/* Variable to define result */
int8_t rslt;
/* Null-pointer check */
rslt = null_ptr_check(dev);
if (rslt == BMI2_OK)
{
/* Assign chip id of BMI270 */
dev->chip_id = BMI270_MAXIMUM_FIFO_CHIP_ID;
dev->config_size = sizeof(bmi270_maximum_fifo_config_file);
/* Enable the variant specific features if any */
dev->variant_feature = BMI2_GYRO_CROSS_SENS_ENABLE | BMI2_MAXIMUM_FIFO_VARIANT;
/* An extra dummy byte is read during SPI read */
if (dev->intf == BMI2_SPI_INTF)
{
dev->dummy_byte = 1;
}
else
{
dev->dummy_byte = 0;
}
/* If configuration file pointer is not assigned any address */
if (!dev->config_file_ptr)
{
/* Give the address of the configuration file array to
* the device pointer
*/
dev->config_file_ptr = bmi270_maximum_fifo_config_file;
}
/* Initialize BMI2 sensor */
rslt = bmi2_sec_init(dev);
if (rslt == BMI2_OK)
{
/* Assign the offsets of the feature input
* configuration to the device structure
*/
dev->feat_config = bmi270_maximum_fifo_feat_in;
/* Assign the offsets of the feature output to
* the device structure
*/
dev->feat_output = bmi270_maximum_fifo_feat_out;
/* Assign the maximum number of pages to the
* device structure
*/
dev->page_max = BMI270_MAXIMUM_FIFO_MAX_PAGE_NUM;
/* Assign maximum number of input sensors/
* features to device structure
*/
dev->input_sens = BMI270_MAXIMUM_FIFO_MAX_FEAT_IN;
/* Assign maximum number of output sensors/
* features to device structure
*/
dev->out_sens = BMI270_MAXIMUM_FIFO_MAX_FEAT_OUT;
/* Get the gyroscope cross axis sensitivity */
rslt = bmi2_get_gyro_cross_sense(dev);
}
}
return rslt;
}
/***************************************************************************/
/*! Local Function Definitions
****************************************************************************/
/*!
* @brief This internal API is used to validate the device structure pointer for
* null conditions.
*/
static int8_t null_ptr_check(const struct bmi2_dev *dev)
{
/* Variable to define result */
int8_t rslt = BMI2_OK;
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_us == NULL))
{
/* Device structure pointer is not valid */
rslt = BMI2_E_NULL_PTR;
}
return rslt;
}
#endif

View file

@ -197,7 +197,13 @@ static bool bmp388StartUP(baroDev_t *baro)
static bool bmp388GetUP(baroDev_t *baro)
{
busReadBuf(baro->busDev, BMP388_DATA_0_REG, sensor_data, BMP388_DATA_FRAME_SIZE + 1);
if (baro->busDev->busType == BUSTYPE_SPI) {
// In SPI mode, first byte read is a dummy byte
busReadBuf(baro->busDev, BMP388_DATA_0_REG, &sensor_data[0], BMP388_DATA_FRAME_SIZE + 1);
} else {
// In I2C mode, no dummy byte is read
busReadBuf(baro->busDev, BMP388_DATA_0_REG, &sensor_data[1], BMP388_DATA_FRAME_SIZE);
}
bmp388_up = sensor_data[1] << 0 | sensor_data[2] << 8 | sensor_data[3] << 16;
bmp388_ut = sensor_data[4] << 0 | sensor_data[5] << 8 | sensor_data[6] << 16;
@ -289,14 +295,26 @@ STATIC_UNIT_TESTED bool bmp388Calculate(baroDev_t *baro, int32_t *pressure, int3
#define DETECTION_MAX_RETRY_COUNT 5
static bool deviceDetect(busDevice_t * busDev)
{
for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) {
uint8_t chipId[2];
uint8_t chipId[2];
uint8_t nRead;
uint8_t * pId;
if (busDev->busType == BUSTYPE_SPI) {
// In SPI mode, first byte read is a dummy byte
nRead = 2;
pId = &chipId[1];
} else {
// In I2C mode, no dummy byte is read
nRead = 1;
pId = &chipId[0];
}
for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) {
delay(100);
bool ack = busReadBuf(busDev, BMP388_CHIP_ID_REG, chipId, 2);
bool ack = busReadBuf(busDev, BMP388_CHIP_ID_REG, chipId, nRead);
if (ack && chipId[1] == BMP388_DEFAULT_CHIP_ID) {
if (ack && *pId == BMP388_DEFAULT_CHIP_ID) {
return true;
}
};
@ -318,11 +336,16 @@ bool bmp388Detect(baroDev_t *baro)
return false;
}
uint8_t calibration_buf[sizeof(bmp388_calib_param_t) + 1];
// read calibration
busReadBuf(baro->busDev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, calibration_buf, sizeof(bmp388_calib_param_t) + 1);
memcpy(&bmp388_cal, calibration_buf + 1, sizeof(bmp388_calib_param_t));
if (baro->busDev->busType == BUSTYPE_SPI) {
// In SPI mode, first byte read is a dummy byte
uint8_t calibration_buf[sizeof(bmp388_calib_param_t) + 1];
busReadBuf(baro->busDev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, calibration_buf, sizeof(bmp388_calib_param_t) + 1);
memcpy(&bmp388_cal, calibration_buf + 1, sizeof(bmp388_calib_param_t));
} else {
// In I2C mode, no dummy byte is read
busReadBuf(baro->busDev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, (uint8_t*)&bmp388_cal, sizeof(bmp388_calib_param_t));
}
// set oversampling + power mode (forced), and start sampling
busWrite(baro->busDev, BMP388_OSR_REG,

View file

@ -95,6 +95,7 @@ typedef enum {
DEVHW_BMI088_ACC,
DEVHW_ICM20689,
DEVHW_ICM42605,
DEVHW_BMI270,
/* Combined ACC/GYRO/MAG chips */
DEVHW_MPU9250,

View file

@ -196,7 +196,15 @@ static void flashConfigurePartitions(void)
#endif
#if defined(CONFIG_IN_EXTERNAL_FLASH)
createPartition(FLASH_PARTITION_TYPE_CONFIG, EEPROM_SIZE, &endSector);
uint32_t configSize = EEPROM_SIZE;
flashSector_t configSectors = (configSize / flashGeometry->sectorSize);
if (configSize % flashGeometry->sectorSize > 0) {
configSectors++; // needs a portion of a sector.
}
configSize = configSectors * flashGeometry->sectorSize;
createPartition(FLASH_PARTITION_TYPE_CONFIG, configSize, &endSector);
#endif
#ifdef USE_FLASHFS

View file

@ -68,6 +68,7 @@ static flashGeometry_t geometry = {.pageSize = M25P16_PAGESIZE};
static busDevice_t * busDev = NULL;
static bool isLargeFlash = false;
static uint32_t timeoutAt = 0;
/*
* Whether we've performed an action that could have made the device busy for writes.
@ -114,15 +115,30 @@ bool m25p16_isReady(void)
return !couldBeBusy;
}
static void m25p16_setTimeout(uint32_t timeoutMillis)
{
uint32_t now = millis();
timeoutAt = now + timeoutMillis;
}
bool m25p16_waitForReady(uint32_t timeoutMillis)
{
uint32_t time = millis();
uint32_t timeoutAtUse;
if (timeoutMillis == 0) {
timeoutAtUse = timeoutAt;
}
else {
timeoutAtUse = millis() + timeoutMillis;
}
while (!m25p16_isReady()) {
if (timeoutMillis && (millis() - time > timeoutMillis)) {
uint32_t now = millis();
if (now >= timeoutAtUse) {
return false;
}
}
timeoutAt = 0;
return true;
}
@ -216,10 +232,6 @@ static bool m25p16_readIdentification(void)
*/
bool m25p16_init(int flashNumToUse)
{
if (busDev) {
return true;
}
busDev = busDeviceInit(BUSTYPE_SPI, DEVHW_M25P16, flashNumToUse, OWNER_FLASH);
if (busDev == NULL) {
return false;
@ -252,20 +264,28 @@ void m25p16_eraseSector(uint32_t address)
m25p16_setCommandAddress(&out[1], address, isLargeFlash);
m25p16_waitForReady(SECTOR_ERASE_TIMEOUT_MILLIS);
if (!m25p16_waitForReady(0)) {
return;
}
m25p16_writeEnable();
busTransfer(busDev, NULL, out, isLargeFlash ? 5 : 4);
m25p16_setTimeout(SECTOR_ERASE_TIMEOUT_MILLIS);
}
void m25p16_eraseCompletely(void)
{
m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS);
if (!m25p16_waitForReady(0)) {
return;
}
m25p16_writeEnable();
m25p16_performOneByteCommand(M25P16_INSTRUCTION_BULK_ERASE);
m25p16_setTimeout(BULK_ERASE_TIMEOUT_MILLIS);
}
/**
@ -294,12 +314,17 @@ uint32_t m25p16_pageProgram(uint32_t address, const uint8_t *data, int length)
m25p16_setCommandAddress(&command[1], address, isLargeFlash);
m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS);
if (!m25p16_waitForReady(0)) {
// return same address to indicate timeout
return address;
}
m25p16_writeEnable();
busTransferMultiple(busDev, txn, 2);
m25p16_setTimeout(DEFAULT_TIMEOUT_MILLIS);
return address + length;
}
@ -322,7 +347,7 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length)
m25p16_setCommandAddress(&command[1], address, isLargeFlash);
if (!m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS)) {
if (!m25p16_waitForReady(0)) {
return 0;
}

View file

@ -23,232 +23,218 @@
#ifdef USE_OSD
#define SYM_RSSI 0x01 // 001 Icon RSSI
#define SYM_AH_LEFT 0x02 // 002 Arrow left
#define SYM_AH_RIGHT 0x03 // 003 Arrow right
#define SYM_THR 0x04 // 004 Throttle
#define SYM_AH_DECORATION_UP 0x05 // 005 Arrow up AHI
#define SYM_VOLT 0x06 // 006 V
#define SYM_MAH 0x07 // 007 MAH
#define SYM_RSSI 0x01 // 001 Icon RSSI
#define SYM_LQ 0x02 // 002 LQ
#define SYM_LAT 0x03 // 003 GPS LAT
#define SYM_LON 0x04 // 004 GPS LON
#define SYM_AZIMUTH 0x05 // 005 Azimuth
#define SYM_TELEMETRY_0 0x06 // 006 Antenna tracking telemetry
#define SYM_TELEMETRY_1 0x07 // 007 Antenna tracking telemetry
#define SYM_SAT_L 0x08 // 008 Sats left
#define SYM_SAT_R 0x09 // 009 Sats right
#define SYM_HOME_NEAR 0x0A // 010 Home, near
#define SYM_DEGREES 0x0B // 011 ° heading angle
#define SYM_HEADING 0x0C // 012 Compass Heading symbol
#define SYM_SCALE 0x0D // 013 Map scale
#define SYM_HDP_L 0x0E // 014 HDOP left
#define SYM_HDP_R 0x0F // 015 HDOP right
#define SYM_HOME 0x10 // 016 Home icon
#define SYM_2RSS 0x11 // 017 RSSI 2
#define SYM_DB 0x12 // 018 dB
#define SYM_DBM 0x13 // 019 dBm
#define SYM_SNR 0x14 // 020 SNR
#define SYM_AH_KM 0x08 // 008 Ah/km
#define SYM_AH_MI 0x09 // 009 Ah/mi
#define SYM_MAH_MI_0 0x0A // 010 mAh/mi left
#define SYM_MAH_MI_1 0x0B // 011 mAh/mi right
#define SYM_LQ 0x0C // 012 LQ
#define SYM_AH_DECORATION_UP 0x15 // 021 Arrow up AHI
#define SYM_AH_DECORATION_DOWN 0x16 // 022 Arrow down AHI
#define SYM_DIRECTION 0x17 // 023 to 030, directional little arrows
#define SYM_TEMP_F 0x0D // 013 °F
#define SYM_TEMP_C 0x0E // 014 °C
#define SYM_FT 0x0F // 015 FT
#define SYM_VOLT 0x1F // 031 VOLTS
#define SYM_MAH 0x99 // 153 mAh
// 0x21 // 033 ASCII !
#define SYM_AH_KM 0x22 // 034 Ah/km
// 0x23 // 035 ASCII #
#define SYM_AH_MI 0x24 // 036 Ah/mi
// 0x25 // 037 ASCII %
// 0x26 // 038 ASCII &
// 0x28 // 040 to 062 ASCII
#define SYM_AH_NM 0x3F // 063 Ah/NM
// 0x40 // 064 to 095 ASCII
#define SYM_MAH_NM_0 0x60 // 096 mAh/NM left
#define SYM_MAH_NM_1 0x61 // 097 mAh/NM right
#define SYM_MAH_KM_0 0x6B // 107 MAH/KM left
#define SYM_MAH_KM_1 0x6C // 108 MAH/KM right
#define SYM_MILLIOHM 0x62 // 098 battery impedance Mohm
#define SYM_AH_DECORATION_MIN 0x10 // 016 to 021 Scrolling
#define SYM_AH_DECORATION 0x13 // 019 Scrolling
#define SYM_AH_DECORATION_MAX 0x15 // 021 Scrolling
#define SYM_BATT_FULL 0x63 // 099 Battery full
#define SYM_BATT_5 0x64 // 100 Battery
#define SYM_BATT_4 0x65 // 101 Battery
#define SYM_BATT_3 0x66 // 102 Battery
#define SYM_BATT_2 0x67 // 103 Battery
#define SYM_BATT_1 0x68 // 104 Battery
#define SYM_BATT_EMPTY 0x69 // 105 Battery empty
#define SYM_AMP 0x6A // 106 AMPS
#define SYM_WH 0x6D // 109 WH
#define SYM_WH_KM 0x6E // 110 WH/KM
#define SYM_WH_MI 0x6F // 111 WH/MI
#define SYM_WH_NM 0x70 // 112 Wh/NM
#define SYM_WATT 0x71 // 113 WATTS
#define SYM_MW 0x72 // 114 mW
#define SYM_KILOWATT 0x73 // 115 kW
#define SYM_FT 0x74 // 116 FEET
#define SYM_TRIP_DIST 0x75 // 117 Trip distance
#define SYM_TOTAL 0x75 // 117 Total
#define SYM_ALT_M 0x76 // 118 ALT M
#define SYM_ALT_KM 0x77 // 119 ALT KM
#define SYM_ALT_FT 0x78 // 120 ALT FT
#define SYM_ALT_KFT 0x79 // 121 Alt KFT
#define SYM_DIST_M 0x7A // 122 DIS M
// 0x7B // 123 to 125 ASCII
#define SYM_DIST_KM 0x7E // 126 DIST KM
#define SYM_DIST_FT 0x7F // 127 DIST FT
#define SYM_DIST_MI 0x80 // 128 DIST MI
#define SYM_DIST_NM 0x81 // 129 DIST NM
#define SYM_M 0x82 // 130 M
#define SYM_KM 0x83 // 131 KM
#define SYM_MI 0x84 // 132 MI
#define SYM_NM 0x85 // 133 NM
#define SYM_WIND_HORIZONTAL 0x86 // 134 Air speed horizontal
#define SYM_WIND_VERTICAL 0x87 // 135 Air speed vertical
#define SYM_3D_KMH 0x88 // 136 KM/H 3D
#define SYM_3D_MPH 0x89 // 137 MPH 3D
#define SYM_3D_KT 0x8A // 138 Knots 3D
#define SYM_RPM 0x8B // 139 RPM
#define SYM_AIR 0x8C // 140 Air speed
#define SYM_FTS 0x8D // 141 FT/S
#define SYM_100FTM 0x8E // 142 100 Feet per Min
#define SYM_MS 0x8F // 143 M/S
#define SYM_KMH 0x90 // 144 KM/H
#define SYM_MPH 0x91 // 145 MPH
#define SYM_KT 0x92 // 146 Knots
#define SYM_MAH_MI_0 0x93 // 147 mAh/mi left
#define SYM_MAH_MI_1 0x94 // 148 mAh/mi right
#define SYM_THR 0x95 // 149 Throttle
#define SYM_TEMP_F 0x96 // 150 °F
#define SYM_TEMP_C 0x97 // 151 °C
// 0x98 // 152 Home point map
#define SYM_BLANK 0x20 // 32 blank (space)
#define SYM_ON_H 0x9A // 154 ON HR
#define SYM_FLY_H 0x9B // 155 FLY HR
#define SYM_ON_M 0x9E // 158 On MIN
#define SYM_FLY_M 0x9F // 159 FL MIN
#define SYM_GLIDESLOPE 0x9C // 156 Glideslope
#define SYM_WAYPOINT 0x9D // 157 Waypoint
#define SYM_CLOCK 0xA0 // 160 Clock
#define SYM_ZERO_HALF_TRAILING_DOT 0xA1 // 161 to 170 Numbers with trailing dot
#define SYM_ZERO_HALF_LEADING_DOT 0xB1 // 177 to 186 Numbers with leading dot
#define SYM_AUTO_THR0 0xAB // 171 Auto-throttle left
#define SYM_AUTO_THR1 0xAC // 172 Auto-throttle right
#define SYM_ROLL_LEFT 0xAD // 173 Sym roll left
#define SYM_ROLL_LEVEL 0xAE // 174 Sym roll horizontal
#define SYM_ROLL_RIGHT 0xAF // 175 Sym roll right
#define SYM_PITCH_UP 0xB0 // 176 Pitch up
#define SYM_PITCH_DOWN 0xBB // 187 Pitch down
#define SYM_GFORCE 0xBC // 188 Gforce (all axis)
#define SYM_GFORCE_X 0xBD // 189 Gforce X
#define SYM_GFORCE_Y 0xBE // 190 Gforce Y
#define SYM_GFORCE_Z 0xBF // 191 Gforce Z
#define SYM_BARO_TEMP 0xC0 // 192
#define SYM_IMU_TEMP 0xC1 // 193
#define SYM_TEMP 0xC2 // 194 Thermometer icon
#define SYM_TEMP_SENSOR_FIRST 0xC2 // 194
#define SYM_ESC_TEMP 0xC3 // 195
#define SYM_TEMP_SENSOR_LAST 0xC7 // 199
#define TEMP_SENSOR_SYM_COUNT (SYM_TEMP_SENSOR_LAST - SYM_TEMP_SENSOR_FIRST + 1)
#define SYM_HEADING_N 0xC8 // 200 Heading Graphic north
#define SYM_HEADING_S 0xC9 // 201 Heading Graphic south
#define SYM_HEADING_E 0xCA // 202 Heading Graphic east
#define SYM_HEADING_W 0xCB // 203 Heading Graphic west
#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic
#define SYM_HEADING_LINE 0xCD // 205 Heading Graphic
#define SYM_MAX 0xCE // 206 MAX symbol
#define SYM_LOGO_START 0x101 // 257 to 280, INAV logo
#define SYM_LOGO_WIDTH 6
#define SYM_LOGO_HEIGHT 4
#define SYM_AH_LEFT 0x12C // 300 Arrow left
#define SYM_AH_RIGHT 0x12D // 301 Arrow right
#define SYM_AH_DECORATION_MIN 0x12E // 302 to 307 Scrolling
#define SYM_AH_DECORATION 0x131 // 305 Scrolling
#define SYM_AH_DECORATION_MAX 0x133 // 307 Scrolling
#define SYM_AH_DECORATION_COUNT (SYM_AH_DECORATION_MAX - SYM_AH_DECORATION_MIN + 1) // Scrolling
#define SYM_WIND_HORIZONTAL 0x16 // 022 Air speed horizontal
#define SYM_WIND_VERTICAL 0x17 // 023 Air speed vertical
#define SYM_AH_CH_LEFT 0x13A // 314 Crossair left
#define SYM_AH_CH_RIGHT 0x13B // 315 Crossair right
#define SYM_HEADING_N 0x18 // 024 Heading Graphic north
#define SYM_HEADING_S 0x19 // 025 Heading Graphic south
#define SYM_HEADING_E 0x1A // 026 Heading Graphic east
#define SYM_HEADING_W 0x1B // 027 Heading Graphic west
#define SYM_HEADING_DIVIDED_LINE 0x1C // 028 Heading Graphic
#define SYM_HEADING_LINE 0x1D // 029 Heading Graphic
#define SYM_ARROW_UP 0x13C // 316 Direction arrow 0°
#define SYM_ARROW_2 0x13D // 317 Direction arrow 22.5°
#define SYM_ARROW_3 0x13E // 318 Direction arrow 45°
#define SYM_ARROW_4 0x13F // 319 Direction arrow 67.5°
#define SYM_ARROW_RIGHT 0x140 // 320 Direction arrow 90°
#define SYM_ARROW_6 0x141 // 321 Direction arrow 112.5°
#define SYM_ARROW_7 0x142 // 322 Direction arrow 135°
#define SYM_ARROW_8 0x143 // 323 Direction arrow 157.5°
#define SYM_ARROW_DOWN 0x144 // 324 Direction arrow 180°
#define SYM_ARROW_10 0x145 // 325 Direction arrow 202.5°
#define SYM_ARROW_11 0x146 // 326 Direction arrow 225°
#define SYM_ARROW_12 0x147 // 327 Direction arrow 247.5°
#define SYM_ARROW_LEFT 0x148 // 328 Direction arrow 270°
#define SYM_ARROW_14 0x149 // 329 Direction arrow 292.5°
#define SYM_ARROW_15 0x14A // 330 Direction arrow 315°
#define SYM_ARROW_16 0x14B // 331 Direction arrow 337.5°
#define SYM_SAT_L 0x1E // 030 Sats left
#define SYM_SAT_R 0x1F // 031 Sats right
#define SYM_AH_H_START 0x14C // 332 to 340 Horizontal AHI
#define SYM_AH_V_START 0x15A // 346 to 351 Vertical AHI
#define SYM_BLANK 0x20 // 032 blank (space)
#define SYM_VARIO_UP_2A 0x155 // 341 Vario up up
#define SYM_VARIO_UP_1A 0x156 // 342 Vario up
#define SYM_VARIO_DOWN_1A 0x157 // 343 Vario down
#define SYM_VARIO_DOWN_2A 0x158 // 344 Vario down down
#define SYM_ALT 0x159 // 345 ALT
// 0x21 // 033 ASCII !
#define SYM_HUD_SIGNAL_0 0x160 // 352 Hud signal icon Lost
#define SYM_HUD_SIGNAL_1 0x161 // 353 Hud signal icon 25%
#define SYM_HUD_SIGNAL_2 0x162 // 354 Hud signal icon 50%
#define SYM_HUD_SIGNAL_3 0x163 // 355 Hud signal icon 75%
#define SYM_HUD_SIGNAL_4 0x164 // 356 Hud signal icon 100%
#define SYM_TRIP_DIST 0x22 // 034 Trip distance
#define SYM_TOTAL 0x22 // 034 Total
#define SYM_HOME_DIST 0x165 // 357 DIST
#define SYM_AH_CH_CENTER 0x166 // 358 Crossair center
// 0x23 // 035 ASCII #
#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3
#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4
#define SYM_AH_CH_TYPE5 0x196 // 406 to 408, crosshair 5
#define SYM_AH_CH_TYPE6 0x199 // 409 to 411, crosshair 6
#define SYM_AH_CH_TYPE7 0x19C // 412 to 414, crosshair 7
#define SYM_AH_CH_TYPE8 0x19F // 415 to 417, crosshair 8
#define SYM_AH_DECORATION_DOWN 0x24 // 036 Arrow down AHI
// 0x25 // 037 ASCII %
#define SYM_AH_CH_LEFT 0x26 // 038 Crossair left
#define SYM_AH_CH_RIGHT 0x27 // 039 Crossair right
// 0x28 // 040 to 062 ASCII
#define SYM_MILLIOHM 0x3F // 063 battery impedance Mohm
// 0x40 // 064 to 095 ASCII
#define SYM_ARROW_UP 0x60 // 096 Direction arrow 0°
#define SYM_ARROW_2 0x61 // 097 Direction arrow 22.5°
#define SYM_ARROW_3 0x62 // 098 Direction arrow 45°
#define SYM_ARROW_4 0x63 // 099 Direction arrow 67.5°
#define SYM_ARROW_RIGHT 0x64 // 100 Direction arrow 90°
#define SYM_ARROW_6 0x65 // 101 Direction arrow 112.5°
#define SYM_ARROW_7 0x66 // 102 Direction arrow 135°
#define SYM_ARROW_8 0x67 // 103 Direction arrow 157.5°
#define SYM_ARROW_DOWN 0x68 // 104 Direction arrow 180°
#define SYM_ARROW_10 0x69 // 105 Direction arrow 202.5°
#define SYM_ARROW_11 0x6A // 106 Direction arrow 225°
#define SYM_ARROW_12 0x6B // 107 Direction arrow 247.5°
#define SYM_ARROW_LEFT 0x6C // 108 Direction arrow 270°
#define SYM_ARROW_14 0x6D // 109 Direction arrow 292.5°
#define SYM_ARROW_15 0x6E // 110 Direction arrow 315°
#define SYM_ARROW_16 0x6F // 111 Direction arrow 337.5°
#define SYM_ON_H 0x70 // 112 ON HR
#define SYM_FLY_H 0x71 // 113 FLY HR
#define SYM_DIRECTION 0x72 // 114 to 121, directional little arrows
#define SYM_HOME_NEAR 0x7A // 122 Home, near
// 0x7B // 123 to 125 ASCII
#define SYM_AH_CH_CENTER 0x7E // 126 Crossair center
#define SYM_GLIDESLOPE 0x7F // 127 Glideslope
#define SYM_AH_H_START 0x80 // 128 to 136 Horizontal AHI
#define SYM_3D_KMH 0x89 // 137 KM/H 3D
#define SYM_3D_MPH 0x8A // 138 MPH 3D
#define SYM_RPM 0x8B // 139 RPM
#define SYM_WAYPOINT 0x8C // 140 Waypoint
#define SYM_AZIMUTH 0x8D // 141 Azimuth
#define SYM_TELEMETRY_0 0x8E // 142 Antenna tracking telemetry
#define SYM_TELEMETRY_1 0x8F // 143 Antenna tracking telemetry
#define SYM_BATT_FULL 0x90 // 144 Battery full
#define SYM_BATT_5 0x91 // 145 Battery
#define SYM_BATT_4 0x92 // 146 Battery
#define SYM_BATT_3 0x93 // 147 Battery
#define SYM_BATT_2 0x94 // 148 Battery
#define SYM_BATT_1 0x95 // 149 Battery
#define SYM_BATT_EMPTY 0x96 // 150 Battery empty
#define SYM_AIR 0x97 // 151 Air speed
// 0x98 // 152 Home point map
#define SYM_FTS 0x99 // 153 FT/S
#define SYM_AMP 0x9A // 154 A
#define SYM_ON_M 0x9B // 155 On MN
#define SYM_FLY_M 0x9C // 156 FL MN
#define SYM_MAH_KM_0 0x9D // 157 MAH/KM left
#define SYM_MAH_KM_1 0x9E // 158 MAH/KM right
#define SYM_MS 0x9F // 159 M/S
#define SYM_HOME_DIST 0xA0 // 160 DIS
#define SYM_KMH 0xA1 // 161 KM/H
#define SYM_VARIO_UP_2A 0xA2 // 162 Vario up up
#define SYM_VARIO_UP_1A 0xA3 // 163 Vario up
#define SYM_VARIO_DOWN_1A 0xA4 // 164 Vario down
#define SYM_VARIO_DOWN_2A 0xA5 // 165 Vario down down
#define SYM_LAT 0xA6 // 166 GPS LAT
#define SYM_LON 0xA7 // 167 GPS LON
#define SYM_DEGREES 0xA8 // 168 ° heading angle
#define SYM_HEADING 0xA9 // 169 Compass Heading symbol
#define SYM_ALT 0xAA // 170 ALT
#define SYM_WH 0xAB // 171 WH
#define SYM_WH_KM 0xAC // 172 WH/KM
#define SYM_WH_MI 0xAD // 173 WH/MI
#define SYM_WATT 0xAE // 174 W
#define SYM_SCALE 0xAF // 175 Map scale
#define SYM_MPH 0xB0 // 176 MPH
#define SYM_ALT_M 0xB1 // 177 ALT M
#define SYM_ALT_KM 0xB2 // 178 ALT KM
#define SYM_ALT_FT 0xB3 // 179 ALT FT
#define SYM_ALT_KFT 0xB4 // 180 DIS KFT
#define SYM_DIST_M 0xB5 // 181 DIS M
#define SYM_DIST_KM 0xB6 // 182 DIM KM
#define SYM_DIST_FT 0xB7 // 183 DIS FT
#define SYM_DIST_MI 0xB8 // 184 DIS MI
#define SYM_M 0xB9 // 185 M
#define SYM_KM 0xBA // 186 KM
#define SYM_MI 0xBB // 187 MI
#define SYM_CLOCK 0xBC // 188 Clock
#define SYM_HDP_L 0xBD // 189 HDOP left
#define SYM_HDP_R 0xBE // 190 HDOP right
#define SYM_HOME 0xBF // 191 Home icon
#define SYM_ZERO_HALF_TRAILING_DOT 0xC0 // 192 to 201 Numbers with trailing dot
#define SYM_AUTO_THR0 0xCA // 202 Auto-throttle left
#define SYM_AUTO_THR1 0xCB // 203 Auto-throttle right
#define SYM_ROLL_LEFT 0xCC // 204 Sym roll left
#define SYM_ROLL_LEVEL 0xCD // 205 Sym roll horizontal
#define SYM_ROLL_RIGHT 0xCE // 206 Sym roll right
#define SYM_PITCH_UP 0xCF // 207 Pitch up
#define SYM_ZERO_HALF_LEADING_DOT 0xD0 // 208 to 217 Numbers with leading dot
#define SYM_AH_CH_AIRCRAFT0 0xDA // 218 Crossair aircraft left
#define SYM_AH_CH_AIRCRAFT1 0xDB // 219 Crossair aircraft
#define SYM_AH_CH_AIRCRAFT2 0xDC // 220 Crossair aircraft center
#define SYM_AH_CH_AIRCRAFT3 0xDD // 221 Crossair aircraft
#define SYM_AH_CH_AIRCRAFT4 0xDE // 222 Crossair aircraft right
#define SYM_PITCH_DOWN 0xDF // 223 Pitch down
#define SYM_AH_V_START 0xE0 // 224 to 229 Vertical AHI
#define SYM_GFORCE 0xE6 // 230 Gforce (all axis)
#define SYM_GFORCE_X 0xE7 // 231 Gforce X
#define SYM_GFORCE_Y 0xE8 // 232 Gforce Y
#define SYM_GFORCE_Z 0xE9 // 233 Gforce Z
#define SYM_BARO_TEMP 0xF0 // 240
#define SYM_IMU_TEMP 0xF1 // 241
#define SYM_TEMP 0xF2 // 242
#define SYM_ESC_TEMP 0xF3 // 243
#define SYM_TEMP_SENSOR_FIRST 0xF2 // 242
#define SYM_TEMP_SENSOR_LAST 0xF7 // 247
#define TEMP_SENSOR_SYM_COUNT (SYM_TEMP_SENSOR_LAST - SYM_TEMP_SENSOR_FIRST + 1)
#define SYM_HUD_SIGNAL_0 0xF8 // 248 Hud signal icon Lost
#define SYM_HUD_SIGNAL_1 0xF9 // 249 Hud signal icon 25%
#define SYM_HUD_SIGNAL_2 0xFA // 250 Hud signal icon 50%
#define SYM_HUD_SIGNAL_3 0xFB // 251 Hud signal icon 75%
#define SYM_HUD_SIGNAL_4 0xFC // 252 Hud signal icon 100%
#define SYM_LOGO_START 0x101 // 257 to 280, INAV logo
#define SYM_LOGO_WIDTH 6
#define SYM_LOGO_HEIGHT 4
#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3
#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4
#define SYM_AH_CH_TYPE5 0x196 // 406 to 408, crosshair 5
#define SYM_AH_CH_TYPE6 0x199 // 409 to 411, crosshair 6
#define SYM_AH_CH_TYPE7 0x19C // 412 to 414, crosshair 7
#define SYM_HUD_ARROWS_L1 0x1A2 // 418 1 arrow left
#define SYM_HUD_ARROWS_L2 0x1A3 // 419 2 arrows left
#define SYM_HUD_ARROWS_L3 0x1A4 // 420 3 arrows left
#define SYM_HUD_ARROWS_R1 0x1A5 // 421 1 arrow right
#define SYM_HUD_ARROWS_R2 0x1A6 // 422 2 arrows right
#define SYM_HUD_ARROWS_R3 0x1A7 // 423 3 arrows right
#define SYM_HUD_ARROWS_U1 0x1A8 // 424 1 arrow up
#define SYM_HUD_ARROWS_U2 0x1A9 // 425 2 arrows up
#define SYM_HUD_ARROWS_U3 0x1AA // 426 3 arrows up
#define SYM_HUD_ARROWS_D1 0x1AB // 427 1 arrow down
#define SYM_HUD_ARROWS_D2 0x1AC // 428 2 arrows down
#define SYM_HUD_ARROWS_D3 0x1AD // 429 3 arrows down
#define SYM_2RSS 0xEA // RSSI 2
#define SYM_DB 0xEB // dB
#define SYM_DBM 0xEC // dBm
#define SYM_SNR 0xEE // SNR
#define SYM_MW 0xED // mW
#define SYM_KILOWATT 0xEF // 239 kW
#define SYM_AH_CH_AIRCRAFT0 0x1A2 // 418 Crossair aircraft left
#define SYM_AH_CH_AIRCRAFT1 0x1A3 // 419 Crossair aircraft
#define SYM_AH_CH_AIRCRAFT2 0x1A4 // 420 Crossair aircraft center
#define SYM_AH_CH_AIRCRAFT3 0x1A5 // 421 Crossair aircraft
#define SYM_AH_CH_AIRCRAFT4 0x1A6 // 422 Crossair aircraft RIGHT
#define SYM_HUD_ARROWS_L1 0x1AE // 430 1 arrow left
#define SYM_HUD_ARROWS_L2 0x1AF // 431 2 arrows left
#define SYM_HUD_ARROWS_L3 0x1B0 // 432 3 arrows left
#define SYM_HUD_ARROWS_R1 0x1B1 // 433 1 arrow right
#define SYM_HUD_ARROWS_R2 0x1B2 // 434 2 arrows right
#define SYM_HUD_ARROWS_R3 0x1B3 // 435 3 arrows right
#define SYM_HUD_ARROWS_U1 0x1B4 // 436 1 arrow up
#define SYM_HUD_ARROWS_U2 0x1B5 // 437 2 arrows up
#define SYM_HUD_ARROWS_U3 0x1B6 // 438 3 arrows up
#define SYM_HUD_ARROWS_D1 0x1B7 // 439 1 arrow down
#define SYM_HUD_ARROWS_D2 0x1B8 // 440 2 arrows down
#define SYM_HUD_ARROWS_D3 0x1B9 // 441 3 arrows down
#else

View file

@ -36,7 +36,6 @@
#include "drivers/pwm_mapping.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
//#include "drivers/rx_pwm.h"
#include "sensors/rangefinder.h"

View file

@ -146,7 +146,7 @@ static pwmOutputPort_t *pwmOutAllocatePort(void)
return p;
}
static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput)
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timHw, resourceOwner_e owner, uint32_t hz, uint16_t period, uint16_t value, bool enableOutput)
{
// Attempt to allocate TCH
TCH_t * tch = timerGetTCH(timHw);
@ -161,7 +161,7 @@ static pwmOutputPort_t *pwmOutConfigMotor(const timerHardware_t *timHw, uint32_t
}
const IO_t io = IOGetByTag(timHw->tag);
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
IOInit(io, owner, RESOURCE_OUTPUT, allocatedOutputPortCount);
if (enableOutput) {
IOConfigGPIOAF(io, IOCFG_AF_PP, timHw->alternateFunction);
@ -228,7 +228,7 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl
const uint32_t timerHz = baseClockHz / prescaler;
const uint32_t period = timerHz / motorPwmRateHz;
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, timerHz, period, 0, enableOutput);
pwmOutputPort_t * port = pwmOutConfig(timerHardware, OWNER_MOTOR, timerHz, period, 0, enableOutput);
if (port) {
port->pulseScale = ((sLen == 0) ? period : (sLen * timerHz)) / 1000.0f;
@ -256,7 +256,7 @@ uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware, uint32_t dshotHz, bool enableOutput)
{
// Try allocating new port
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, dshotHz, DSHOT_MOTOR_BITLENGTH, 0, enableOutput);
pwmOutputPort_t * port = pwmOutConfig(timerHardware, OWNER_MOTOR, dshotHz, DSHOT_MOTOR_BITLENGTH, 0, enableOutput);
if (!port) {
return NULL;
@ -580,7 +580,7 @@ void pwmServoPreconfigure(void)
bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput)
{
pwmOutputPort_t * port = pwmOutConfigMotor(timerHardware, PWM_TIMER_HZ, PWM_TIMER_HZ / servoPwmRate, servoCenterPulse, enableOutput);
pwmOutputPort_t * port = pwmOutConfig(timerHardware, OWNER_SERVO, PWM_TIMER_HZ, PWM_TIMER_HZ / servoPwmRate, servoCenterPulse, enableOutput);
if (port) {
servos[servoIndex] = port;

View file

@ -1,248 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#if defined(USE_RX_PPM)
#include "build/build_config.h"
#include "build/debug.h"
#include "common/utils.h"
#include "drivers/time.h"
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "timer.h"
#include "pwm_output.h"
#include "pwm_mapping.h"
#include "rx_pwm.h"
#define PPM_CAPTURE_COUNT 16
#define INPUT_FILTER_TICKS 10
#define PPM_TIMER_PERIOD 0x10000
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
static uint16_t captures[PPM_CAPTURE_COUNT];
static uint8_t ppmFrameCount = 0;
static uint8_t lastPPMFrameCount = 0;
static uint8_t ppmCountDivisor = 1;
typedef struct ppmDevice_s {
uint8_t pulseIndex;
uint32_t currentCapture;
uint32_t currentTime;
uint32_t deltaTime;
uint32_t captures[PPM_CAPTURE_COUNT];
uint32_t largeCounter;
int8_t numChannels;
int8_t numChannelsPrevFrame;
uint8_t stableFramesSeenCount;
bool tracking;
bool overflowed;
} ppmDevice_t;
ppmDevice_t ppmDev;
#define PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
#define PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
#define PPM_STABLE_FRAMES_REQUIRED_COUNT 25
#define PPM_IN_MIN_NUM_CHANNELS 4
#define PPM_IN_MAX_NUM_CHANNELS PPM_CAPTURE_COUNT
bool isPPMDataBeingReceived(void)
{
return (ppmFrameCount != lastPPMFrameCount);
}
void resetPPMDataReceivedState(void)
{
lastPPMFrameCount = ppmFrameCount;
}
#define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4
static void ppmInit(void)
{
ppmDev.pulseIndex = 0;
ppmDev.currentCapture = 0;
ppmDev.currentTime = 0;
ppmDev.deltaTime = 0;
ppmDev.largeCounter = 0;
ppmDev.numChannels = -1;
ppmDev.numChannelsPrevFrame = -1;
ppmDev.stableFramesSeenCount = 0;
ppmDev.tracking = false;
ppmDev.overflowed = false;
}
static void ppmOverflowCallback(struct TCH_s * tch, uint32_t capture)
{
UNUSED(tch);
ppmDev.largeCounter += capture + 1;
if (capture == PPM_TIMER_PERIOD - 1) {
ppmDev.overflowed = true;
}
}
static void ppmEdgeCallback(struct TCH_s * tch, uint32_t capture)
{
UNUSED(tch);
int32_t i;
uint32_t previousTime = ppmDev.currentTime;
uint32_t previousCapture = ppmDev.currentCapture;
/* Grab the new count */
uint32_t currentTime = capture;
/* Convert to 32-bit timer result */
currentTime += ppmDev.largeCounter;
if (capture < previousCapture) {
if (ppmDev.overflowed) {
currentTime += PPM_TIMER_PERIOD;
}
}
// Divide to match output protocol
currentTime = currentTime / ppmCountDivisor;
/* Capture computation */
if (currentTime > previousTime) {
ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD / ppmCountDivisor) : 0));
} else {
ppmDev.deltaTime = (PPM_TIMER_PERIOD / ppmCountDivisor) + currentTime - previousTime;
}
ppmDev.overflowed = false;
/* Store the current measurement */
ppmDev.currentTime = currentTime;
ppmDev.currentCapture = capture;
#if 0
static uint32_t deltaTimes[20];
static uint8_t deltaIndex = 0;
deltaIndex = (deltaIndex + 1) % 20;
deltaTimes[deltaIndex] = ppmDev.deltaTime;
UNUSED(deltaTimes);
#endif
#if 0
static uint32_t captureTimes[20];
static uint8_t captureIndex = 0;
captureIndex = (captureIndex + 1) % 20;
captureTimes[captureIndex] = capture;
UNUSED(captureTimes);
#endif
/* Sync pulse detection */
if (ppmDev.deltaTime > PPM_IN_MIN_SYNC_PULSE_US) {
if (ppmDev.pulseIndex == ppmDev.numChannelsPrevFrame
&& ppmDev.pulseIndex >= PPM_IN_MIN_NUM_CHANNELS
&& ppmDev.pulseIndex <= PPM_IN_MAX_NUM_CHANNELS) {
/* If we see n simultaneous frames of the same
number of channels we save it as our frame size */
if (ppmDev.stableFramesSeenCount < PPM_STABLE_FRAMES_REQUIRED_COUNT) {
ppmDev.stableFramesSeenCount++;
} else {
ppmDev.numChannels = ppmDev.pulseIndex;
}
} else {
ppmDev.stableFramesSeenCount = 0;
}
/* Check if the last frame was well formed */
if (ppmDev.pulseIndex == ppmDev.numChannels && ppmDev.tracking) {
/* The last frame was well formed */
for (i = 0; i < ppmDev.numChannels; i++) {
captures[i] = ppmDev.captures[i];
}
for (i = ppmDev.numChannels; i < PPM_IN_MAX_NUM_CHANNELS; i++) {
captures[i] = PPM_RCVR_TIMEOUT;
}
ppmFrameCount++;
}
ppmDev.tracking = true;
ppmDev.numChannelsPrevFrame = ppmDev.pulseIndex;
ppmDev.pulseIndex = 0;
/* We rely on the supervisor to set captureValue to invalid
if no valid frame is found otherwise we ride over it */
} else if (ppmDev.tracking) {
/* Valid pulse duration 0.75 to 2.5 ms*/
if (ppmDev.deltaTime > PPM_IN_MIN_CHANNEL_PULSE_US
&& ppmDev.deltaTime < PPM_IN_MAX_CHANNEL_PULSE_US
&& ppmDev.pulseIndex < PPM_IN_MAX_NUM_CHANNELS) {
ppmDev.captures[ppmDev.pulseIndex] = ppmDev.deltaTime;
ppmDev.pulseIndex++;
} else {
/* Not a valid pulse duration */
ppmDev.tracking = false;
for (i = 0; i < PPM_CAPTURE_COUNT; i++) {
ppmDev.captures[i] = PPM_RCVR_TIMEOUT;
}
}
}
}
bool ppmInConfig(const timerHardware_t *timerHardwarePtr)
{
static timerCallbacks_t callbacks;
TCH_t * tch = timerGetTCH(timerHardwarePtr);
if (tch == NULL) {
return false;
}
ppmInit();
IO_t io = IOGetByTag(timerHardwarePtr->tag);
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
IOConfigGPIOAF(io, timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
timerConfigure(tch, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_HZ);
timerChInitCallbacks(&callbacks, (void*)&ppmDev, &ppmEdgeCallback, &ppmOverflowCallback);
timerChConfigCallbacks(tch, &callbacks);
timerChConfigIC(tch, true, INPUT_FILTER_TICKS);
timerChCaptureEnable(tch);
return true;
}
uint16_t ppmRead(uint8_t channel)
{
return captures[channel];
}
#endif

View file

@ -1,32 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define PPM_RCVR_TIMEOUT 0
struct timerHardware_s;
bool ppmInConfig(const struct timerHardware_s *timerHardwarePtr);
void pwmInConfig(const struct timerHardware_s *timerHardwarePtr, uint8_t channel);
uint16_t pwmRead(uint8_t channel);
uint16_t ppmRead(uint8_t channel);
bool isPPMDataBeingReceived(void);
void resetPPMDataReceivedState(void);
bool isPWMDataBeingReceived(void);

View file

@ -1385,14 +1385,19 @@ bool SD_Init(void)
// Initialize SDMMC1 peripheral interface with default configuration for SD card initialization
MODIFY_REG(SDMMC1->CLKCR, CLKCR_CLEAR_MASK, (uint32_t) SDMMC_INIT_CLK_DIV);
delay(100);
// Identify card operating voltage
if ((ErrorState = SD_PowerON()) == SD_OK) {
delay(100);
// Initialize the present card and put them in idle state
if ((ErrorState = SD_InitializeCard()) == SD_OK) {
delay(100);
// Read CSD/CID MSD registers
if ((ErrorState = SD_GetCardInfo()) == SD_OK) {
// Select the Card - Send CMD7 SDMMC_SEL_DESEL_CARD
ErrorState = SD_TransmitCommand((SD_CMD_SEL_DESEL_CARD | SD_CMD_RESPONSE_SHORT), SD_CardRCA, 1);
delay(100);
MODIFY_REG(SDMMC1->CLKCR, CLKCR_CLEAR_MASK, (uint32_t) SDMMC_CLK_DIV); // Configure SDMMC1 peripheral interface
}
}
@ -1400,12 +1405,14 @@ bool SD_Init(void)
// Configure SD Bus width
if (ErrorState == SD_OK) {
delay(100);
// Enable wide operation
#ifdef SDCARD_SDIO_4BIT
ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_4B);
#else
ErrorState = SD_WideBusOperationConfig(SD_BUS_WIDE_1B);
#endif
delay(100);
}
// Configure the SDCARD device

View file

@ -50,8 +50,8 @@ typedef struct uartDevice_s {
#ifdef USE_UART1
#define UART_PIN_AF_UART1_PA9 GPIO_AF7_USART1
#define UART_PIN_AF_UART1_PA10 GPIO_AF7_USART1
#define UART_PIN_AF_UART1_PB6 GPIO_AF4_USART1
#define UART_PIN_AF_UART1_PB7 GPIO_AF4_USART1
#define UART_PIN_AF_UART1_PB6 GPIO_AF7_USART1
#define UART_PIN_AF_UART1_PB7 GPIO_AF7_USART1
#define UART_PIN_AF_UART1_PB14 GPIO_AF4_USART1
#define UART_PIN_AF_UART1_PB15 GPIO_AF4_USART1
@ -470,4 +470,4 @@ void UART8_IRQHandler(void)
uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port);
uartIrqHandler(s);
}
#endif
#endif

View file

@ -30,7 +30,8 @@ typedef enum {
FAILURE_ACC_INCOMPATIBLE,
FAILURE_INVALID_EEPROM_CONTENTS,
FAILURE_FLASH_WRITE_FAILED,
FAILURE_GYRO_INIT_FAILED
FAILURE_GYRO_INIT_FAILED,
FAILURE_FLASH_READ_FAILED,
} failureMode_e;
// failure

View file

@ -138,7 +138,7 @@
#define DEF_TIM_AF__PA1__TCH_TIM15_CH1N D(4, 15)
#define DEF_TIM_AF__PA2__TCH_TIM15_CH1 D(4, 15)
#define DEF_TIM_AF__PA2__TCH_TIM15_CH2 D(4, 15)
#define DEF_TIM_AF__PA3__TCH_TIM15_CH2 D(4, 15)
//PORTB
#define DEF_TIM_AF__PB0__TCH_TIM1_CH2N D(1, 1)

View file

@ -60,7 +60,6 @@ uint8_t cliMode = 0;
#include "drivers/io_impl.h"
#include "drivers/osd_symbols.h"
#include "drivers/persistent.h"
#include "drivers/rx_pwm.h"
#include "drivers/sdcard/sdcard.h"
#include "drivers/sensor.h"
#include "drivers/serial.h"
@ -162,9 +161,15 @@ static const char * const featureNames[] = {
"OSD", "FW_LAUNCH", "FW_AUTOTRIM", NULL
};
#ifdef USE_BLACKBOX
static const char * const blackboxIncludeFlagNames[] = {
"NAV_ACC", "NAV_POS", "NAV_PID", "MAG", "ACC", "ATTI", NULL
};
#endif
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
// sync with gyroSensor_e
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "FAKE"};
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"};
// sync this with sensors_e
static const char * const sensorTypeNames[] = {
@ -2504,6 +2509,94 @@ static void cliFeature(char *cmdline)
}
}
#ifdef USE_BLACKBOX
static void printBlackbox(uint8_t dumpMask, const blackboxConfig_t *config, const blackboxConfig_t *configDefault)
{
UNUSED(configDefault);
uint32_t mask = config->includeFlags;
for (uint8_t i = 0; ; i++) { // reenable what we want.
if (blackboxIncludeFlagNames[i] == NULL) {
break;
}
const char *formatOn = "blackbox %s";
const char *formatOff = "blackbox -%s";
if (mask & (1 << i)) {
cliDumpPrintLinef(dumpMask, false, formatOn, blackboxIncludeFlagNames[i]);
cliDefaultPrintLinef(dumpMask, false, formatOn, blackboxIncludeFlagNames[i]);
} else {
cliDumpPrintLinef(dumpMask, false, formatOff, blackboxIncludeFlagNames[i]);
cliDefaultPrintLinef(dumpMask, false, formatOff, blackboxIncludeFlagNames[i]);
}
}
}
static void cliBlackbox(char *cmdline)
{
uint32_t len = strlen(cmdline);
uint32_t mask = blackboxConfig()->includeFlags;
if (len == 0) {
cliPrint("Enabled: ");
for (uint8_t i = 0; ; i++) {
if (blackboxIncludeFlagNames[i] == NULL) {
break;
}
if (mask & (1 << i))
cliPrintf("%s ", blackboxIncludeFlagNames[i]);
}
cliPrintLinefeed();
} else if (sl_strncasecmp(cmdline, "list", len) == 0) {
cliPrint("Available: ");
for (uint32_t i = 0; ; i++) {
if (blackboxIncludeFlagNames[i] == NULL) {
break;
}
cliPrintf("%s ", blackboxIncludeFlagNames[i]);
}
cliPrintLinefeed();
return;
} else {
bool remove = false;
if (cmdline[0] == '-') {
// remove feature
remove = true;
cmdline++; // skip over -
len--;
}
for (uint32_t i = 0; ; i++) {
if (blackboxIncludeFlagNames[i] == NULL) {
cliPrintErrorLine("Invalid name");
break;
}
if (sl_strncasecmp(cmdline, blackboxIncludeFlagNames[i], len) == 0) {
mask = 1 << i;
if (remove) {
blackboxIncludeFlagClear(mask);
cliPrint("Disabled");
} else {
blackboxIncludeFlagSet(mask);
cliPrint("Enabled");
}
cliPrintLinef(" %s", blackboxIncludeFlagNames[i]);
break;
}
}
}
}
#endif
#if defined(BEEPER) || defined(USE_DSHOT)
static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
{
@ -3186,14 +3279,15 @@ static void cliStatus(char *cmdline)
cliPrintLinef(" PCLK2 = %d MHz", clocks.PCLK2_Frequency / 1000000);
#endif
cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s",
cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s, IMU2=%s",
hardwareSensorStatusNames[getHwGyroStatus()],
hardwareSensorStatusNames[getHwAccelerometerStatus()],
hardwareSensorStatusNames[getHwCompassStatus()],
hardwareSensorStatusNames[getHwBarometerStatus()],
hardwareSensorStatusNames[getHwRangefinderStatus()],
hardwareSensorStatusNames[getHwOpticalFlowStatus()],
hardwareSensorStatusNames[getHwGPSStatus()]
hardwareSensorStatusNames[getHwGPSStatus()],
hardwareSensorStatusNames[getHwSecondaryImuStatus()]
);
#ifdef USE_ESC_SENSOR
@ -3504,6 +3598,11 @@ static void printConfig(const char *cmdline, bool doDiff)
printBeeper(dumpMask, &beeperConfig_Copy, beeperConfig());
#endif
#ifdef USE_BLACKBOX
cliPrintHashLine("blackbox");
printBlackbox(dumpMask, &blackboxConfig_Copy, blackboxConfig());
#endif
cliPrintHashLine("map");
printMap(dumpMask, &rxConfig_Copy, rxConfig());
@ -3697,6 +3796,11 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("feature", "configure features",
"list\r\n"
"\t<+|->[name]", cliFeature),
#ifdef USE_BLACKBOX
CLI_COMMAND_DEF("blackbox", "configure blackbox fields",
"list\r\n"
"\t<+|->[name]", cliBlackbox),
#endif
#ifdef USE_FLASHFS
CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),

View file

@ -107,7 +107,7 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
.enabledFeatures = DEFAULT_FEATURES | COMMON_DEFAULT_FEATURES
);
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 3);
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 4);
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.current_profile_index = 0,
@ -193,13 +193,6 @@ void validateAndFixConfig(void)
// Disable unused features
featureClear(FEATURE_UNUSED_1 | FEATURE_UNUSED_3 | FEATURE_UNUSED_4 | FEATURE_UNUSED_5 | FEATURE_UNUSED_6 | FEATURE_UNUSED_7 | FEATURE_UNUSED_8 | FEATURE_UNUSED_9 | FEATURE_UNUSED_10);
#if !defined(USE_RX_PPM)
if (rxConfig()->receiverType == RX_TYPE_PPM) {
rxConfigMutable()->receiverType = RX_TYPE_NONE;
}
#endif
#if defined(USE_LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
if (featureConfigured(FEATURE_SOFTSERIAL) && featureConfigured(FEATURE_LED_STRIP)) {
const timerHardware_t *ledTimerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);

View file

@ -22,7 +22,6 @@
#include "common/time.h"
#include "config/parameter_group.h"
#include "drivers/adc.h"
#include "drivers/rx_pwm.h"
#include "fc/stats.h"
#define MAX_PROFILE_COUNT 3
@ -30,7 +29,7 @@
#define MAX_NAME_LENGTH 16
#define TASK_GYRO_LOOPTIME 250 // Task gyro always runs at 4kHz
typedef enum {
typedef enum {
FEATURE_THR_VBAT_COMP = 1 << 0,
FEATURE_VBAT = 1 << 1,
FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command

View file

@ -63,7 +63,6 @@
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_output.h"
#include "drivers/rx_pwm.h"
#include "drivers/sensor.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"
@ -217,6 +216,13 @@ void init(void)
detectBrushedESC();
#endif
#ifdef CONFIG_IN_EXTERNAL_FLASH
// Reset config to defaults. Note: Default flash config must be functional for config in external flash to work.
pgResetAll(0);
flashDeviceInitialized = flashInit();
#endif
initEEPROM();
ensureEEPROMContainsValidData();
readEEPROM();
@ -270,15 +276,7 @@ void init(void)
timerInit(); // timer must be initialized before any channel is allocated
#if defined(AVOID_UART2_FOR_PWM_PPM)
serialInit(feature(FEATURE_SOFTSERIAL),
(rxConfig()->receiverType == RX_TYPE_PPM) ? SERIAL_PORT_USART2 : SERIAL_PORT_NONE);
#elif defined(AVOID_UART3_FOR_PWM_PPM)
serialInit(feature(FEATURE_SOFTSERIAL),
(rxConfig()->receiverType == RX_TYPE_PPM) ? SERIAL_PORT_USART3 : SERIAL_PORT_NONE);
#else
serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
#endif
serialInit(feature(FEATURE_SOFTSERIAL));
// Initialize MSP serial ports here so LOG can share a port with MSP.
// XXX: Don't call mspFcInit() yet, since it initializes the boxes and needs
@ -360,6 +358,11 @@ void init(void)
// Initialize buses
busInit();
#ifdef CONFIG_IN_EXTERNAL_FLASH
// busInit re-configures the SPI pins. Init flash again so it is ready to write settings
flashDeviceInitialized = flashInit();
#endif
#ifdef USE_HARDWARE_REVISION_DETECTION
updateHardwareRevision();
#endif

View file

@ -76,6 +76,7 @@
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/servos.h"
#include "flight/secondary_imu.h"
#include "config/config_eeprom.h"
#include "config/feature.h"
@ -424,6 +425,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, getHwRangefinderStatus());
sbufWriteU8(dst, getHwPitotmeterStatus());
sbufWriteU8(dst, getHwOpticalFlowStatus());
sbufWriteU8(dst, getHwSecondaryImuStatus());
break;
case MSP_ACTIVEBOXES:

View file

@ -39,8 +39,11 @@
#define AVAILABLE_FIRMWARE_SPACE (FLASH_END - FIRMWARE_START_ADDRESS)
extern uint8_t __firmware_start; // set via linker
#if defined(CONFIG_IN_FLASH)
extern uint8_t __config_start;
extern uint8_t __config_end;
#endif
typedef struct {
uint32_t magic;

View file

@ -4,7 +4,7 @@ tables:
- name: gyro_lpf
values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"]
- name: acc_hardware
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "FAKE"]
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"]
enum: accelerationSensor_e
- name: rangefinder_hardware
values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
@ -25,7 +25,7 @@ tables:
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
enum: pitotSensor_e
- name: receiver_type
values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UNUSED"]
values: ["NONE", "SERIAL", "MSP", "SPI"]
enum: rxReceiverType_e
- name: serial_rx
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
@ -64,7 +64,7 @@ tables:
- name: nav_rth_alt_mode
values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST", "AT_LEAST_LINEAR_DESCENT"]
- name: osd_unit
values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK"]
values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK", "GA"]
enum: osd_unit_e
- name: osd_stats_energy_unit
values: ["MAH", "WH"]
@ -93,7 +93,7 @@ tables:
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "FW_D", "IMU2", "ALTITUDE",
"IRLOCK", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "IMU2", "ALTITUDE",
"GYRO_ALPHA_BETA_GAMMA", "SMITH_PREDICTOR", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS"]
- name: async_mode
values: ["NONE", "GYRO", "ALL"]
@ -101,7 +101,7 @@ tables:
values: ["OR", "AND"]
enum: modeActivationOperator_e
- name: osd_crosshairs_style
values: ["DEFAULT", "AIRCRAFT", "TYPE3", "TYPE4", "TYPE5", "TYPE6", "TYPE7"]
values: ["DEFAULT", "AIRCRAFT", "TYPE3", "TYPE4", "TYPE5", "TYPE6", "TYPE7", "TYPE8"]
enum: osd_crosshairs_style_e
- name: osd_sidebar_scroll
values: ["NONE", "ALTITUDE", "SPEED", "HOME_DISTANCE"]
@ -1493,7 +1493,7 @@ groups:
members:
- name: imu_dcm_kp
description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
default_value: 2500
default_value: 1000
field: dcm_kp_acc
max: UINT16_MAX
- name: imu_dcm_ki
@ -1503,7 +1503,7 @@ groups:
max: UINT16_MAX
- name: imu_dcm_kp_mag
description: "Inertial Measurement Unit KP Gain for compass measurements"
default_value: 10000
default_value: 5000
field: dcm_kp_mag
max: UINT16_MAX
- name: imu_dcm_ki_mag
@ -3111,7 +3111,12 @@ groups:
field: stats_min_voltage_unit
table: osd_stats_min_voltage_unit
type: uint8_t
- name: osd_stats_page_auto_swap_time
description: "Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0."
default_value: 3
field: stats_page_auto_swap_time
min: 0
max: 10
- name: osd_rssi_alarm
description: "Value below which to make the OSD RSSI indicator blink"
default_value: 20

View file

@ -107,7 +107,7 @@ typedef struct {
bool itermLimitActive;
bool itermFreezeActive;
pt2Filter_t rateTargetFilter;
pt3Filter_t rateTargetFilter;
smithPredictor_t smithPredictor;
} pidState_t;
@ -123,7 +123,11 @@ STATIC_FASTRAM bool pidGainsUpdateRequired;
FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT];
#ifdef USE_BLACKBOX
int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_D[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_Setpoint[FLIGHT_DYNAMICS_INDEX_COUNT];
int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT];
int32_t axisPID_I[FLIGHT_DYNAMICS_INDEX_COUNT];
int32_t axisPID_D[FLIGHT_DYNAMICS_INDEX_COUNT];
int32_t axisPID_F[FLIGHT_DYNAMICS_INDEX_COUNT];
int32_t axisPID_Setpoint[FLIGHT_DYNAMICS_INDEX_COUNT];
#endif
static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
@ -339,7 +343,7 @@ bool pidInitFilters(void)
if (pidProfile()->controlDerivativeLpfHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
pt2FilterInit(&pidState[axis].rateTargetFilter, pt2FilterGain(pidProfile()->controlDerivativeLpfHz, refreshRate * 1e-6f));
pt3FilterInit(&pidState[axis].rateTargetFilter, pt3FilterGain(pidProfile()->controlDerivativeLpfHz, refreshRate * 1e-6f));
}
}
@ -540,7 +544,7 @@ void updatePIDCoefficients()
pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * axisTPA;
pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER;
pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * axisTPA;
pidState[axis].kCD = pidBank()->pid[axis].FF / FP_PID_RATE_D_FF_MULTIPLIER * axisTPA;
pidState[axis].kCD = (pidBank()->pid[axis].FF / FP_PID_RATE_D_FF_MULTIPLIER * axisTPA) / (getLooptime() * 0.000001f);
pidState[axis].kFF = 0.0f;
// Tracking anti-windup requires P/I/D to be all defined which is only true for MC
@ -747,7 +751,6 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh
const float newDTerm = dTermProcess(pidState, dT);
const float newFFTerm = pidState->rateTarget * pidState->kFF;
DEBUG_SET(DEBUG_FW_D, axis, newDTerm);
/*
* Integral should be updated only if axis Iterm is not frozen
*/
@ -773,6 +776,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh
axisPID_P[axis] = newPTerm;
axisPID_I[axis] = pidState->errorGyroIf;
axisPID_D[axis] = newDTerm;
axisPID_F[axis] = newFFTerm;
axisPID_Setpoint[axis] = pidState->rateTarget;
#endif
@ -803,13 +807,12 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
const float newDTerm = dTermProcess(pidState, dT);
const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget;
const float rateTargetDeltaFiltered = pt2FilterApply(&pidState->rateTargetFilter, rateTargetDelta);
const float rateTargetDeltaFiltered = pt3FilterApply(&pidState->rateTargetFilter, rateTargetDelta);
/*
* Compute Control Derivative
*/
const float newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT);
DEBUG_SET(DEBUG_CD, axis, newCDTerm);
const float newCDTerm = rateTargetDeltaFiltered * pidState->kCD;
// TODO: Get feedback from mixer on available correction range for each axis
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm;
@ -833,6 +836,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
axisPID_P[axis] = newPTerm;
axisPID_I[axis] = pidState->errorGyroIf;
axisPID_D[axis] = newDTerm;
axisPID_F[axis] = newCDTerm;
axisPID_Setpoint[axis] = pidState->rateTarget;
#endif

View file

@ -189,7 +189,7 @@ const pidBank_t * pidBank(void);
pidBank_t * pidBankMutable(void);
extern int16_t axisPID[];
extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[];
extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_F[], axisPID_Setpoint[];
void pidInit(void);
bool pidInitFilters(void);

View file

@ -95,10 +95,13 @@ void secondaryImuInit(void)
calibrationData.radius[ACC] = secondaryImuConfig()->calibrationRadiusAcc;
calibrationData.radius[MAG] = secondaryImuConfig()->calibrationRadiusMag;
requestedSensors[SENSOR_INDEX_IMU2] = secondaryImuConfig()->hardwareType;
if (secondaryImuConfig()->hardwareType == SECONDARY_IMU_BNO055) {
secondaryImuState.active = bno055Init(calibrationData, (secondaryImuConfig()->calibrationRadiusAcc && secondaryImuConfig()->calibrationRadiusMag));
if (secondaryImuState.active) {
detectedSensors[SENSOR_INDEX_IMU2] = SECONDARY_IMU_BNO055;
rescheduleTask(TASK_SECONDARY_IMU, TASK_PERIOD_HZ(10));
}
@ -106,12 +109,13 @@ void secondaryImuInit(void)
secondaryImuState.active = bno055SerialInit(calibrationData, (secondaryImuConfig()->calibrationRadiusAcc && secondaryImuConfig()->calibrationRadiusMag));
if (secondaryImuState.active) {
detectedSensors[SENSOR_INDEX_IMU2] = SECONDARY_IMU_BNO055_SERIAL;
rescheduleTask(TASK_SECONDARY_IMU, TASK_PERIOD_HZ(50));
}
}
if (!secondaryImuState.active) {
secondaryImuConfigMutable()->hardwareType = SECONDARY_IMU_NONE;
detectedSensors[SENSOR_INDEX_IMU2] = SECONDARY_IMU_NONE;
}
}
@ -223,3 +227,33 @@ void secondaryImuFetchCalibration(void) {
void secondaryImuSetMagneticDeclination(float declination) { //Incoming units are degrees
secondaryImuState.magDeclination = declination * 10.0f; //Internally declination is stored in decidegrees
}
bool isSecondaryImuHealthy(void) {
return secondaryImuState.active;
}
hardwareSensorStatus_e getHwSecondaryImuStatus(void)
{
#ifdef USE_SECONDARY_IMU
if (detectedSensors[SENSOR_INDEX_IMU2] != SECONDARY_IMU_NONE) {
if (isSecondaryImuHealthy()) {
return HW_SENSOR_OK;
}
else {
return HW_SENSOR_UNHEALTHY;
}
}
else {
if (requestedSensors[SENSOR_INDEX_IMU2] != SECONDARY_IMU_NONE) {
// Selected but not detected
return HW_SENSOR_UNAVAILABLE;
}
else {
// Not selected and not detected
return HW_SENSOR_NONE;
}
}
#else
return HW_SENSOR_NONE;
#endif
}

View file

@ -29,6 +29,7 @@
#include "sensors/sensors.h"
#include "drivers/accgyro/accgyro_bno055.h"
#include "drivers/accgyro/accgyro_bno055_serial.h"
#include "sensors/diagnostics.h"
typedef enum {
SECONDARY_IMU_NONE = 0,
@ -66,4 +67,6 @@ void secondaryImuProcess(void);
void secondaryImuInit(void);
void taskSecondaryImu(timeUs_t currentTimeUs);
void secondaryImuFetchCalibration(void);
void secondaryImuSetMagneticDeclination(float declination);
void secondaryImuSetMagneticDeclination(float declination);
bool isSecondaryImuHealthy(void);
hardwareSensorStatus_e getHwSecondaryImuStatus(void);

View file

@ -183,9 +183,9 @@ static bool NAZA_parse_gps(void)
uint32_t v_acc = decodeLong(_buffernaza.nav.v_acc, mask); // mm
//uint32_t test = decodeLong(_buffernaza.nav.reserved, mask);
gpsSol.velNED[0] = decodeLong(_buffernaza.nav.ned_north, mask); // cm/s
gpsSol.velNED[1] = decodeLong(_buffernaza.nav.ned_east, mask); // cm/s
gpsSol.velNED[2] = decodeLong(_buffernaza.nav.ned_down, mask); // cm/s
gpsSol.velNED[X] = decodeLong(_buffernaza.nav.ned_north, mask); // cm/s
gpsSol.velNED[Y] = decodeLong(_buffernaza.nav.ned_east, mask); // cm/s
gpsSol.velNED[Z] = decodeLong(_buffernaza.nav.ned_down, mask); // cm/s
uint16_t pdop = decodeShort(_buffernaza.nav.pdop, mask); // pdop
@ -199,10 +199,10 @@ static bool NAZA_parse_gps(void)
gpsSol.eph = gpsConstrainEPE(h_acc / 10); // hAcc in cm
gpsSol.epv = gpsConstrainEPE(v_acc / 10); // vAcc in cm
gpsSol.numSat = _buffernaza.nav.satellites;
gpsSol.groundSpeed = fast_fsqrtf(powf(gpsSol.velNED[0], 2)+powf(gpsSol.velNED[1], 2)); //cm/s
gpsSol.groundSpeed = fast_fsqrtf(powf(gpsSol.velNED[X], 2) + powf(gpsSol.velNED[Y], 2)); //cm/s
// calculate gps heading from VELNE
gpsSol.groundCourse = (uint16_t) (fmodf(RADIANS_TO_DECIDEGREES(atan2_approx(gpsSol.velNED[1], gpsSol.velNED[0]))+3600.0f,3600.0f));
gpsSol.groundCourse = (uint16_t)(fmodf(RADIANS_TO_DECIDEGREES(atan2_approx(gpsSol.velNED[Y], gpsSol.velNED[X])) + 3600.0f, 3600.0f));
gpsSol.flags.validVelNE = 1;
gpsSol.flags.validVelD = 1;

View file

@ -587,9 +587,9 @@ static bool gpsParceFrameUBLOX(void)
case MSG_VELNED:
gpsSol.groundSpeed = _buffer.velned.speed_2d; // cm/s
gpsSol.groundCourse = (uint16_t) (_buffer.velned.heading_2d / 10000); // Heading 2D deg * 100000 rescaled to deg * 10
gpsSol.velNED[0] = _buffer.velned.ned_north;
gpsSol.velNED[1] = _buffer.velned.ned_east;
gpsSol.velNED[2] = _buffer.velned.ned_down;
gpsSol.velNED[X] = _buffer.velned.ned_north;
gpsSol.velNED[Y] = _buffer.velned.ned_east;
gpsSol.velNED[Z] = _buffer.velned.ned_down;
gpsSol.flags.validVelNE = 1;
gpsSol.flags.validVelD = 1;
_new_speed = true;

View file

@ -145,7 +145,7 @@ FILE_COMPILE_FOR_SPEED
#define OSD_CENTER_LEN(x) ((osdDisplayPort->cols - x) / 2)
#define OSD_CENTER_S(s) OSD_CENTER_LEN(strlen(s))
#define OSD_MIN_FONT_VERSION 2
#define OSD_MIN_FONT_VERSION 3
static unsigned currentLayout = 0;
static int layoutOverride = -1;
@ -156,6 +156,8 @@ static float GForce, GForceAxis[XYZ_AXIS_COUNT];
typedef struct statistic_s {
uint16_t max_speed;
uint16_t max_3D_speed;
uint16_t max_air_speed;
uint16_t min_voltage; // /100
int16_t max_current;
int32_t max_power;
@ -337,6 +339,14 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals)
}
buff[4] = '\0';
break;
case OSD_UNIT_GA:
if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_NAUTICALMILE, decimals, 3, 3)) {
buff[3] = SYM_DIST_NM;
} else {
buff[3] = SYM_DIST_FT;
}
buff[4] = '\0';
break;
}
}
@ -373,6 +383,17 @@ static void osdFormatDistanceStr(char *buff, int32_t dist)
(abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM);
}
break;
case OSD_UNIT_GA:
centifeet = CENTIMETERS_TO_CENTIFEET(dist);
if (abs(centifeet) < 100000) {
// Show feet when dist < 1000ft
tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT);
} else {
// Show nautical miles when dist >= 1000ft
tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)),
(int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), SYM_NM);
}
break;
}
}
@ -388,9 +409,11 @@ static int32_t osdConvertVelocityToUnit(int32_t vel)
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
return (vel * 224) / 10000; // Convert to mph
return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph
case OSD_UNIT_METRIC:
return (vel * 36) / 1000; // Convert to kmh
return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh
case OSD_UNIT_GA:
return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots
}
// Unreachable
return -1;
@ -400,7 +423,7 @@ static int32_t osdConvertVelocityToUnit(int32_t vel)
* Converts velocity into a string based on the current unit system.
* @param alt Raw velocity (i.e. as taken from gpsSol.groundSpeed in centimeters/seconds)
*/
void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D)
void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max)
{
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
@ -408,10 +431,25 @@ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D)
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH));
if (_max) {
tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH));
} else {
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH));
}
break;
case OSD_UNIT_METRIC:
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH));
if (_max) {
tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH));
} else {
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH));
}
break;
case OSD_UNIT_GA:
if (_max) {
tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT));
} else {
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT));
}
break;
}
}
@ -433,12 +471,16 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid)
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
centivalue = (ws * 224) / 100;
centivalue = CMSEC_TO_CENTIMPH(ws);
suffix = SYM_MPH;
break;
case OSD_UNIT_GA:
centivalue = CMSEC_TO_CENTIKNOTS(ws);
suffix = SYM_KT;
break;
default:
case OSD_UNIT_METRIC:
centivalue = (ws * 36) / 10;
centivalue = CMSEC_TO_CENTIKPH(ws);
suffix = SYM_KMH;
break;
}
@ -469,6 +511,8 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt)
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_GA:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
if (osdFormatCentiNumber(buff + 4 - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) {
// Scaled to kft
@ -505,6 +549,8 @@ static void osdFormatAltitudeStr(char *buff, int32_t alt)
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_GA:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
value = CENTIMETERS_TO_FEET(alt);
tfp_sprintf(buff, "%d%c", (int)value, SYM_FT);
@ -1072,8 +1118,8 @@ int osdGetHeadingAngle(int angle)
* in-out used to store the last position where the craft was drawn to avoid
* erasing all screen on each redraw.
*/
static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t centerSym,
uint32_t poiDistance, int16_t poiDirection, uint8_t poiSymbol,
static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t centerSym,
uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol,
uint16_t *drawn, uint32_t *usedScale)
{
// TODO: These need to be tested with several setups. We might
@ -1113,6 +1159,9 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
case OSD_UNIT_IMPERIAL:
initialScale = 16; // 16m ~= 0.01miles
break;
case OSD_UNIT_GA:
initialScale = 18; // 18m ~= 0.01 nautical miles
break;
default:
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
@ -1534,14 +1583,20 @@ static bool osdDrawSingleElement(uint8_t item)
break;
case OSD_GPS_SPEED:
osdFormatVelocityStr(buff, gpsSol.groundSpeed, false);
osdFormatVelocityStr(buff, gpsSol.groundSpeed, false, false);
break;
case OSD_GPS_MAX_SPEED:
osdFormatVelocityStr(buff, stats.max_speed, false, true);
break;
case OSD_3D_SPEED:
{
osdFormatVelocityStr(buff, osdGet3DSpeed(), true);
break;
}
osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false);
break;
case OSD_3D_MAX_SPEED:
osdFormatVelocityStr(buff, stats.max_3D_speed, true, true);
break;
case OSD_GLIDESLOPE:
{
@ -1643,7 +1698,8 @@ static bool osdDrawSingleElement(uint8_t item)
} else {
buff[1] = buff[2] = buff[3] = '-';
}
buff[4] = '\0';
buff[4] = SYM_DEGREES;
buff[5] = '\0';
break;
}
@ -1834,13 +1890,27 @@ static bool osdDrawSingleElement(uint8_t item)
#endif
buff[0] = SYM_TRIP_DIST;
if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) {
buff[4] = SYM_DIST_M;
buff[4] = SYM_BLANK;
buff[5] = '\0';
strcpy(buff + 1, "---");
} else if (distanceMeters == -2) {
// Wind is too strong to come back with cruise throttle
buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL;
buff[4] = SYM_DIST_M;
switch ((osd_unit_e)osdConfig()->units){
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
buff[4] = SYM_DIST_MI;
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
buff[4] = SYM_DIST_KM;
break;
case OSD_UNIT_GA:
buff[4] = SYM_DIST_NM;
break;
}
buff[5] = '\0';
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
} else {
@ -2145,6 +2215,11 @@ static bool osdDrawSingleElement(uint8_t item)
value = CENTIMETERS_TO_CENTIFEET(value);
sym = SYM_FTS;
break;
case OSD_UNIT_GA:
// Convert to centi-100feet/min
value = CENTIMETERS_TO_FEET(value * 60);
sym = SYM_100FTM;
break;
default:
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
@ -2351,7 +2426,19 @@ static bool osdDrawSingleElement(uint8_t item)
{
#ifdef USE_PITOT
buff[0] = SYM_AIR;
osdFormatVelocityStr(buff + 1, pitot.airSpeed, false);
osdFormatVelocityStr(buff + 1, pitot.airSpeed, false, false);
#else
return false;
#endif
break;
}
case OSD_AIR_MAX_SPEED:
{
#ifdef USE_PITOT
buff[0] = SYM_MAX;
buff[1] = SYM_AIR;
osdFormatVelocityStr(buff + 2, stats.max_air_speed, false, false);
#else
return false;
#endif
@ -2450,6 +2537,20 @@ static bool osdDrawSingleElement(uint8_t item)
buff[5] = '\0';
}
break;
case OSD_UNIT_GA:
moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, 3);
if (!moreThanAh) {
tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1);
} else {
tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM);
}
if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-';
buff[3] = SYM_MAH_NM_0;
buff[4] = SYM_MAH_NM_1;
buff[5] = '\0';
}
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -2497,6 +2598,10 @@ static bool osdDrawSingleElement(uint8_t item)
osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3);
buff[3] = SYM_WH_MI;
break;
case OSD_UNIT_GA:
osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3);
buff[3] = SYM_WH_NM;
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -2669,7 +2774,8 @@ static bool osdDrawSingleElement(uint8_t item)
} else {
buff[1] = buff[2] = buff[3] = '-';
}
buff[4] = '\0';
buff[4] = SYM_DEGREES;
buff[5] = '\0';
break;
}
@ -2691,6 +2797,13 @@ static bool osdDrawSingleElement(uint8_t item)
symScaled = SYM_MI;
maxDecimals = 2;
break;
case OSD_UNIT_GA:
scaleToUnit = 100 / 1852.0010f; // scale to 0.01mi for osdFormatCentiNumber()
scaleUnitDivisor = 0;
symUnscaled = SYM_NM;
symScaled = SYM_NM;
maxDecimals = 2;
break;
default:
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
@ -3028,7 +3141,8 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.force_grid = SETTING_OSD_FORCE_GRID_DEFAULT,
.stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT,
.stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT
.stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT,
.stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT
);
void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
@ -3234,14 +3348,17 @@ static void osdCompleteAsyncInitialization(void)
y++;
}
y++;
} else {
if (!fontHasMetadata || metadata.version < OSD_MIN_FONT_VERSION) {
const char *m = "INVALID FONT";
displayWrite(osdDisplayPort, OSD_CENTER_S(m), 3, m);
}
} else if (!fontHasMetadata) {
const char *m = "INVALID FONT";
displayWrite(osdDisplayPort, OSD_CENTER_S(m), 3, m);
y = 4;
}
if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) {
const char *m = "INVALID FONT VERSION";
displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m);
}
char string_buffer[30];
tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING);
displayWrite(osdDisplayPort, 5, y++, string_buffer);
@ -3264,6 +3381,10 @@ static void osdCompleteAsyncInitialization(void)
string_buffer[5] = SYM_MI;
break;
default:
case OSD_UNIT_GA:
tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE));
string_buffer[5] = SYM_NM;
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -3296,6 +3417,10 @@ static void osdCompleteAsyncInitialization(void)
osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3);
string_buffer[3] = SYM_WH_MI;
break;
case OSD_UNIT_GA:
osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3);
string_buffer[3] = SYM_WH_NM;
break;
default:
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
@ -3341,6 +3466,8 @@ static void osdResetStats(void)
stats.max_current = 0;
stats.max_power = 0;
stats.max_speed = 0;
stats.max_3D_speed = 0;
stats.max_air_speed = 0;
stats.min_voltage = 5000;
stats.min_rssi = 99;
stats.min_lq = 300;
@ -3354,8 +3481,14 @@ static void osdUpdateStats(void)
if (feature(FEATURE_GPS)) {
value = osdGet3DSpeed();
if (stats.max_speed < value)
stats.max_speed = value;
if (stats.max_3D_speed < value)
stats.max_3D_speed = value;
if (stats.max_speed < gpsSol.groundSpeed)
stats.max_speed = gpsSol.groundSpeed;
if (stats.max_air_speed < pitot.airSpeed)
stats.max_air_speed = pitot.airSpeed;
if (stats.max_distance < GPS_distanceToHome)
stats.max_distance = GPS_distanceToHome;
@ -3404,7 +3537,7 @@ static void osdShowStatsPage1(void)
if (feature(FEATURE_GPS)) {
displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :");
osdFormatVelocityStr(buff, stats.max_speed, true);
osdFormatVelocityStr(buff, stats.max_3D_speed, true, false);
osdLeftAlignString(buff);
displayWrite(osdDisplayPort, statValuesX, top++, buff);
@ -3533,6 +3666,28 @@ static void osdShowStatsPage2(void)
}
}
break;
case OSD_UNIT_GA:
if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) {
moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, 3);
if (!moreThanAh) {
tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1);
} else {
tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM);
}
if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-';
buff[3] = SYM_MAH_NM_0;
buff[4] = SYM_MAH_NM_1;
buff[5] = '\0';
}
} else {
osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, 3);
tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM);
if (!efficiencyValid) {
buff[0] = buff[1] = buff[2] = '-';
}
}
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -3691,9 +3846,11 @@ static void osdRefresh(timeUs_t currentTimeUs)
}
// detect arm/disarm
static uint8_t statsPageAutoSwapCntl = 2;
if (armState != ARMING_FLAG(ARMED)) {
if (ARMING_FLAG(ARMED)) {
osdResetStats();
statsPageAutoSwapCntl = 2;
osdShowArmed(); // reset statistic etc
uint32_t delay = ARMED_SCREEN_DISPLAY_TIME;
statsPagesCheck = 0;
@ -3703,8 +3860,9 @@ static void osdRefresh(timeUs_t currentTimeUs)
#endif
osdSetNextRefreshIn(delay);
} else {
osdShowStatsPage1(); // show first page of statistic
osdShowStatsPage1(); // show first page of statistics
osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME);
statsPageAutoSwapCntl = osdConfig()->stats_page_auto_swap_time > 0 ? 0 : 2; // disable swapping pages when time = 0
}
armState = ARMING_FLAG(ARMED);
@ -3716,6 +3874,26 @@ static void osdRefresh(timeUs_t currentTimeUs)
// Clear the screen first to erase other elements which
// might have been drawn while the OSD wasn't refreshing.
// auto swap stats pages when first shown
// auto swap cancelled using roll stick
if (statsPageAutoSwapCntl != 2) {
if (STATS_PAGE1 || STATS_PAGE2) {
statsPageAutoSwapCntl = 2;
} else {
if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) {
if (statsPageAutoSwapCntl == 0) {
osdShowStatsPage1();
statsPageAutoSwapCntl = 1;
}
} else {
if (statsPageAutoSwapCntl == 1) {
osdShowStatsPage2();
statsPageAutoSwapCntl = 0;
}
}
}
}
if (!DELAYED_REFRESH_RESUME_COMMAND)
refreshWaitForResumeCmdRelease = false;
@ -3895,82 +4073,60 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
// messages to show.
const char *messages[5];
unsigned messageCount = 0;
if (FLIGHT_MODE(FAILSAFE_MODE)) {
// In FS mode while being armed too
const char *failsafePhaseMessage = osdFailsafePhaseMessage();
const char *failsafeInfoMessage = osdFailsafeInfoMessage();
const char *navStateFSMessage = navigationStateMessage();
const char *failsafeInfoMessage = NULL;
if (failsafePhaseMessage) {
messages[messageCount++] = failsafePhaseMessage;
if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
if (isWaypointMissionRTHActive()) {
// if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL);
}
if (failsafeInfoMessage) {
messages[messageCount++] = failsafeInfoMessage;
}
if (navStateFSMessage) {
messages[messageCount++] = navStateFSMessage;
if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED);
} else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) {
// Countdown display for remaining Waypoints
char buf[6];
osdFormatDistanceSymbol(buf, posControl.wpDistance, 0);
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf);
messages[messageCount++] = messageBuf;
} else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) {
// WP hold time countdown in seconds
timeMs_t currentTime = millis();
int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)((currentTime - posControl.wpReachedTime)/1000);
if (holdTimeRemaining >=0) {
tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining);
}
messages[messageCount++] = messageBuf;
} else {
const char *navStateMessage = navigationStateMessage();
if (navStateMessage) {
messages[messageCount++] = navStateMessage;
}
}
#if defined(USE_SAFE_HOME)
const char *safehomeMessage = divertingToSafehomeMessage();
if (safehomeMessage) {
messages[messageCount++] = safehomeMessage;
}
#endif
if (messageCount > 0) {
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)];
if (message == failsafeInfoMessage) {
// failsafeInfoMessage is not useful for recovering
// a lost model, but might help avoiding a crash.
// Blink to grab user attention.
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
}
// We're shoing either failsafePhaseMessage or
// navStateFSMessage. Don't BLINK here since
// having this text available might be crucial
// during a lost aircraft recovery and blinking
// will cause it to be missing from some frames.
if (safehomeMessage) {
messages[messageCount++] = safehomeMessage;
}
} else {
if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
if (isWaypointMissionRTHActive()) {
// if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL);
}
if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED);
} else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) {
// Countdown display for remaining Waypoints
char buf[6];
osdFormatDistanceSymbol(buf, posControl.wpDistance, 0);
tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf);
messages[messageCount++] = messageBuf;
} else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) {
// WP hold time countdown in seconds
timeMs_t currentTime = millis();
int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)((currentTime - posControl.wpReachedTime)/1000);
if (holdTimeRemaining >=0) {
tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining);
messages[messageCount++] = messageBuf;
}
} else {
const char *navStateMessage = navigationStateMessage();
if (navStateMessage) {
messages[messageCount++] = navStateMessage;
}
}
#if defined(USE_SAFE_HOME)
const char *safehomeMessage = divertingToSafehomeMessage();
if (safehomeMessage) {
messages[messageCount++] = safehomeMessage;
}
#endif
} else if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH);
const char *launchStateMessage = fixedWingLaunchStateMessage();
if (launchStateMessage) {
messages[messageCount++] = launchStateMessage;
}
if (FLIGHT_MODE(FAILSAFE_MODE)) {
// In FS mode while being armed too
const char *failsafePhaseMessage = osdFailsafePhaseMessage();
failsafeInfoMessage = osdFailsafeInfoMessage();
if (failsafePhaseMessage) {
messages[messageCount++] = failsafePhaseMessage;
}
if (failsafeInfoMessage) {
messages[messageCount++] = failsafeInfoMessage;
}
}
} else { /* messages shown only when Failsafe, WP, RTH or Emergency Landing not active */
if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH);
const char *launchStateMessage = fixedWingLaunchStateMessage();
if (launchStateMessage) {
messages[messageCount++] = launchStateMessage;
}
} else {
if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) {
// ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO
@ -3992,11 +4148,20 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE);
}
}
// Pick one of the available messages. Each message lasts
// a second.
if (messageCount > 0) {
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)];
}
if (messageCount > 0) {
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)];
if (message == failsafeInfoMessage) {
// failsafeInfoMessage is not useful for recovering
// a lost model, but might help avoiding a crash.
// Blink to grab user attention.
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
}
// We're shoing either failsafePhaseMessage or
// navStateMessage. Don't BLINK here since
// having this text available might be crucial
// during a lost aircraft recovery and blinking
// will cause it to be missing from some frames.
}
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {
unsigned invalidIndex;

View file

@ -231,6 +231,9 @@ typedef enum {
OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
OSD_PLIMIT_ACTIVE_POWER_LIMIT,
OSD_GLIDESLOPE,
OSD_GPS_MAX_SPEED,
OSD_3D_MAX_SPEED,
OSD_AIR_MAX_SPEED,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;
@ -239,8 +242,9 @@ typedef enum {
OSD_UNIT_METRIC,
OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph
OSD_UNIT_UK, // Show everything in imperial, temperature in C
OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C
OSD_UNIT_MAX = OSD_UNIT_UK,
OSD_UNIT_MAX = OSD_UNIT_GA,
} osd_unit_e;
typedef enum {
@ -353,6 +357,7 @@ typedef struct osdConfig_s {
uint8_t units; // from osd_unit_e
uint8_t stats_energy_unit; // from osd_stats_energy_unit_e
uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e
uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds)
#ifdef USE_WIND_ESTIMATOR
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
@ -410,7 +415,7 @@ int32_t osdGetAltitude(void);
void osdCrosshairPosition(uint8_t *x, uint8_t *y);
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length);
void osdFormatAltitudeSymbol(char *buff, int32_t alt);
void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D);
void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max);
// Returns a heading angle in degrees normalized to [0, 360).
int osdGetHeadingAngle(int angle);

View file

@ -438,7 +438,7 @@ void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *can
void osdCanvasDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading)
{
static const uint8_t graph[] = {
static const uint16_t graph[] = {
SYM_HEADING_W,
SYM_HEADING_LINE,
SYM_HEADING_DIVIDED_LINE,
@ -504,6 +504,8 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll)
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_GA:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
return CENTIMETERS_TO_CENTIFEET(osdGetAltitude());
case OSD_UNIT_METRIC_MPH:
@ -524,6 +526,9 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll)
case OSD_UNIT_IMPERIAL:
// cms/s to (mi/h) * 100
return speed * 224 / 100;
case OSD_UNIT_GA:
// cm/s to Knots * 100
return (int)(speed * 0.019438444924406) * 100;
case OSD_UNIT_METRIC:
// cm/s to (km/h) * 100
return speed * 36 / 10;
@ -536,6 +541,8 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll)
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_GA:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
return CENTIMETERS_TO_CENTIFEET(GPS_distanceToHome * 100);
case OSD_UNIT_METRIC_MPH:
@ -583,6 +590,8 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os
switch ((osd_unit_e)osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_GA:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
unit->symbol = SYM_ALT_FT;
unit->divisor = FEET_PER_KILOFEET;
@ -611,6 +620,12 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os
unit->divided_symbol = 0;
*countsPerStep = 5;
break;
case OSD_UNIT_GA:
unit->symbol = SYM_KT;
unit->divisor = 0;
unit->divided_symbol = 0;
*countsPerStep = 5;
break;
case OSD_UNIT_METRIC:
unit->symbol = SYM_KMH;
unit->divisor = 0;
@ -629,6 +644,12 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, os
unit->divided_symbol = SYM_MI;
*countsPerStep = 300;
break;
case OSD_UNIT_GA:
unit->symbol = SYM_FT;
unit->divisor = (int)FEET_PER_NAUTICALMILE;
unit->divided_symbol = SYM_NM;
*countsPerStep = 300;
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -648,7 +669,7 @@ static bool osdCanvasDrawSidebar(uint32_t *configured, displayWidgets_t *widgets
osd_sidebar_scroll_e scroll, unsigned scrollStep)
{
STATIC_ASSERT(OSD_SIDEBAR_SCROLL_MAX <= 3, adjust_scroll_shift);
STATIC_ASSERT(OSD_UNIT_MAX <= 3, adjust_units_shift);
STATIC_ASSERT(OSD_UNIT_MAX <= 5, adjust_units_shift);
// Configuration
uint32_t configuration = scrollStep << 16 | (unsigned)osdConfig()->sidebar_horizontal_offset << 8 | scroll << 6 | osdConfig()->units << 4;
if (configuration != *configured) {

View file

@ -655,9 +655,11 @@ static int32_t osdConvertVelocityToUnit(int32_t vel)
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
return (vel * 224) / 10000; // Convert to mph
return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph
case OSD_UNIT_GA:
return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots
case OSD_UNIT_METRIC:
return (vel * 36) / 1000; // Convert to kmh
return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh
}
// Unreachable
@ -697,6 +699,9 @@ void osdDJIFormatVelocityStr(char* buff)
case OSD_UNIT_IMPERIAL:
tfp_sprintf(buff, "%s %3d MPH", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
case OSD_UNIT_GA:
tfp_sprintf(buff, "%s %3d KT", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
case OSD_UNIT_METRIC:
tfp_sprintf(buff, "%s %3d KPH", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
@ -735,6 +740,18 @@ static void osdDJIFormatDistanceStr(char *buff, int32_t dist)
(abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, "Mi");
}
break;
case OSD_UNIT_GA:
centifeet = CENTIMETERS_TO_CENTIFEET(dist);
if (abs(centifeet) < FEET_PER_NAUTICALMILE * 100 / 2) {
// Show feet when dist < 0.5mi
tfp_sprintf(buff, "%d%s", (int)(centifeet / 100), "FT");
}
else {
// Show miles when dist >= 0.5mi
tfp_sprintf(buff, "%d.%02d%s", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)),
(int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), "NM");
}
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
@ -1165,7 +1182,7 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms
djiSerializeCraftNameOverride(dst);
} else {
#endif
sbufWriteData(dst, systemConfig()->name, MAX((int)strlen(systemConfig()->name), OSD_MESSAGE_LENGTH));
sbufWriteData(dst, systemConfig()->name, (int)strlen(systemConfig()->name));
#if defined(USE_OSD)
}
#endif

View file

@ -59,7 +59,7 @@ typedef struct osd_sidebar_s {
void osdGridDrawVario(displayPort_t *display, unsigned gx, unsigned gy, float zvel)
{
int v = zvel / OSD_VARIO_CM_S_PER_ARROW;
uint8_t vchars[] = {SYM_BLANK, SYM_BLANK, SYM_BLANK, SYM_BLANK, SYM_BLANK};
uint16_t vchars[] = {SYM_BLANK, SYM_BLANK, SYM_BLANK, SYM_BLANK, SYM_BLANK};
if (v >= 6)
vchars[0] = SYM_VARIO_UP_2A;
@ -220,11 +220,11 @@ void osdGridDrawHeadingGraph(displayPort_t *display, unsigned gx, unsigned gy, i
displayWrite(display, gx, gy, buf);
}
static uint8_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *sidebar, timeMs_t currentTimeMs)
static uint16_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *sidebar, timeMs_t currentTimeMs)
{
// Scroll between SYM_AH_DECORATION_MIN and SYM_AH_DECORATION_MAX.
// Zero scrolling should draw SYM_AH_DECORATION.
uint8_t decoration = SYM_AH_DECORATION;
uint16_t decoration = SYM_AH_DECORATION;
int offset = 0;
int steps;
switch (scroll) {
@ -291,8 +291,8 @@ void osdGridDrawSidebars(displayPort_t *display)
static osd_sidebar_t right;
timeMs_t currentTimeMs = millis();
uint8_t leftDecoration = osdUpdateSidebar(osdConfig()->left_sidebar_scroll, &left, currentTimeMs);
uint8_t rightDecoration = osdUpdateSidebar(osdConfig()->right_sidebar_scroll, &right, currentTimeMs);
uint16_t leftDecoration = osdUpdateSidebar(osdConfig()->left_sidebar_scroll, &left, currentTimeMs);
uint16_t rightDecoration = osdUpdateSidebar(osdConfig()->right_sidebar_scroll, &right, currentTimeMs);
const int hudwidth = OSD_AH_SIDEBAR_WIDTH_POS;
const int hudheight = osdConfig()->sidebar_height;

View file

@ -226,6 +226,7 @@ void osdHudDrawCrosshair(displayCanvas_t *canvas, uint8_t px, uint8_t py)
SYM_AH_CH_TYPE5, SYM_AH_CH_TYPE5 + 1, SYM_AH_CH_TYPE5 + 2,
SYM_AH_CH_TYPE6, SYM_AH_CH_TYPE6 + 1, SYM_AH_CH_TYPE6 + 2,
SYM_AH_CH_TYPE7, SYM_AH_CH_TYPE7 + 1, SYM_AH_CH_TYPE7 + 2,
SYM_AH_CH_TYPE8, SYM_AH_CH_TYPE8 + 1, SYM_AH_CH_TYPE8 + 2,
};
// Center on the screen
@ -240,6 +241,11 @@ void osdHudDrawCrosshair(displayCanvas_t *canvas, uint8_t px, uint8_t py)
displayWriteChar(osdGetDisplayPort(), px, py, crh_style_all[crh_crosshair * 3 + 1]);
displayWriteChar(osdGetDisplayPort(), px + 1, py, crh_style_all[crh_crosshair * 3 + 2]);
if ((crh_style_all[crh_crosshair * 3]) == SYM_AH_CH_AIRCRAFT1) {
displayWriteChar(osdGetDisplayPort(), px - 2, py, SYM_AH_CH_AIRCRAFT0);
displayWriteChar(osdGetDisplayPort(), px + 2, py, SYM_AH_CH_AIRCRAFT4);
}
if (canvas) {
displayCanvasContextPop(canvas);
}
@ -345,7 +351,7 @@ void osdHudDrawExtras(uint8_t poi_id)
displayWrite(osdGetDisplayPort(), minX + 4, lineY, buftmp);
osdFormatVelocityStr(buftmp, radar_pois[poi_id].speed, false);
osdFormatVelocityStr(buftmp, radar_pois[poi_id].speed, false, false);
displayWrite(osdGetDisplayPort(), maxX - 9, lineY, buftmp);
tfp_sprintf(buftmp, "%3d%c", radar_pois[poi_id].heading, SYM_HEADING);

View file

@ -441,7 +441,7 @@ void closeSerialPort(serialPort_t *serialPort)
serialPortUsage->serialPort = NULL;
}
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
void serialInit(bool softserialEnabled)
{
uint8_t index;
@ -451,12 +451,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
serialPortUsageList[index].identifier = serialPortIdentifiers[index];
if (serialPortToDisable != SERIAL_PORT_NONE) {
if (serialPortUsageList[index].identifier == serialPortToDisable) {
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
serialPortCount--;
}
}
if (!softserialEnabled) {
if (0
#ifdef USE_SOFTSERIAL1

View file

@ -138,7 +138,7 @@ typedef void serialConsumer(uint8_t);
//
// configuration
//
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
void serialInit(bool softserialEnabled);
void serialRemovePort(serialPortIdentifier_e identifier);
uint8_t serialGetAvailablePortCount(void);
bool serialIsPortAvailable(serialPortIdentifier_e identifier);

View file

@ -199,7 +199,7 @@ navigationPosControl_t posControl;
navSystemStatus_t NAV_Status;
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
#if defined(NAV_BLACKBOX)
// Blackbox states
int16_t navCurrentState;
int16_t navActualVelocity[3];
int16_t navDesiredVelocity[3];
@ -212,7 +212,7 @@ uint16_t navFlags;
uint16_t navEPH;
uint16_t navEPV;
int16_t navAccNEU[3];
#endif
//End of blackbox states
static fpVector3_t * rthGetHomeTargetPosition(rthTargetMode_e mode);
static void updateDesiredRTHAltitude(void);
@ -1116,7 +1116,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
if ((posControl.flags.estHeadingStatus == EST_NONE) || (posControl.flags.estAltStatus == EST_NONE) || !STATE(GPS_FIX_HOME)) {
// Heading sensor, altitude sensor and HOME fix are mandatory for RTH. If not satisfied - switch to emergency landing
// Mainly relevant to failsafe forced RTH since switched RTH blocked in selectNavEventFromBoxModeInput if sensors unavailanle.
// Relevant to failsafe forced RTH only. Switched RTH blocked in selectNavEventFromBoxModeInput if sensors unavailable.
// If we are in dead-reckoning mode - also fail, since coordinates may be unreliable
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
}
@ -1932,12 +1932,11 @@ void updateActualHorizontalPositionAndVelocity(bool estPosValid, bool estVelVali
posControl.flags.horizontalPositionDataNew = 0;
}
#if defined(NAV_BLACKBOX)
//Update blackbox data
navLatestActualPosition[X] = newX;
navLatestActualPosition[Y] = newY;
navActualVelocity[X] = constrain(newVelX, -32678, 32767);
navActualVelocity[Y] = constrain(newVelY, -32678, 32767);
#endif
}
/*-----------------------------------------------------------
@ -1987,10 +1986,9 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo
posControl.actualState.surfaceMin = -1;
}
#if defined(NAV_BLACKBOX)
//Update blackbox data
navLatestActualPosition[Z] = navGetCurrentActualPositionAndVelocity()->pos.z;
navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
#endif
}
/*-----------------------------------------------------------
@ -3048,7 +3046,7 @@ void applyWaypointNavigationAndAltitudeHold(void)
{
const timeUs_t currentTimeUs = micros();
#if defined(NAV_BLACKBOX)
//Updata blackbox data
navFlags = 0;
if (posControl.flags.estAltStatus == EST_TRUSTED) navFlags |= (1 << 0);
if (posControl.flags.estAglStatus == EST_TRUSTED) navFlags |= (1 << 1);
@ -3058,7 +3056,6 @@ void applyWaypointNavigationAndAltitudeHold(void)
if (isGPSGlitchDetected()) navFlags |= (1 << 4);
#endif
if (posControl.flags.estHeadingStatus == EST_TRUSTED) navFlags |= (1 << 5);
#endif
// Reset all navigation requests - NAV controllers will set them if necessary
DISABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
@ -3092,8 +3089,7 @@ void applyWaypointNavigationAndAltitudeHold(void)
if (posControl.flags.verticalPositionDataConsumed)
posControl.flags.verticalPositionDataNew = 0;
#if defined(NAV_BLACKBOX)
//Update blackbox data
if (posControl.flags.isAdjustingPosition) navFlags |= (1 << 6);
if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7);
if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8);
@ -3101,7 +3097,6 @@ void applyWaypointNavigationAndAltitudeHold(void)
navTargetPosition[X] = lrintf(posControl.desiredState.pos.x);
navTargetPosition[Y] = lrintf(posControl.desiredState.pos.y);
navTargetPosition[Z] = lrintf(posControl.desiredState.pos.z);
#endif
}
/*-----------------------------------------------------------
@ -3457,9 +3452,8 @@ void updateWaypointsAndNavigationMode(void)
// Map navMode back to enabled flight modes
switchNavigationFlightModes();
#if defined(NAV_BLACKBOX)
//Update Blackbox data
navCurrentState = (int16_t)posControl.navPersistentId;
#endif
}
/*-----------------------------------------------------------

View file

@ -69,9 +69,6 @@ bool findNearestSafeHome(void); // Find nearest safehome
#endif // defined(USE_SAFE_HOME)
#if defined(USE_NAV)
#if defined(USE_BLACKBOX)
#define NAV_BLACKBOX
#endif
#ifndef NAV_MAX_WAYPOINTS
#define NAV_MAX_WAYPOINTS 15

View file

@ -98,9 +98,7 @@ static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros)
posControl.desiredState.vel.z = targetVel;
}
#if defined(NAV_BLACKBOX)
navDesiredVelocity[Z] = constrain(lrintf(posControl.desiredState.vel.z), -32678, 32767);
#endif
}
static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros)
@ -467,10 +465,8 @@ static void updatePositionVelocityController_MC(const float maxSpeed)
posControl.desiredState.vel.x = newVelX * velHeadFactor * velExpoFactor;
posControl.desiredState.vel.y = newVelY * velHeadFactor * velExpoFactor;
#if defined(NAV_BLACKBOX)
navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
#endif
}
static float computeNormalizedVelocity(const float value, const float maxValue)

View file

@ -246,8 +246,8 @@ void onNewGPSData(void)
/* Use VELNED provided by GPS if available, calculate from coordinates otherwise */
float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f);
if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) {
posEstimator.gps.vel.x = gpsSol.velNED[0];
posEstimator.gps.vel.y = gpsSol.velNED[1];
posEstimator.gps.vel.x = gpsSol.velNED[X];
posEstimator.gps.vel.y = gpsSol.velNED[Y];
}
else {
posEstimator.gps.vel.x = (posEstimator.gps.vel.x + (DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lat - previousLat) / dT)) / 2.0f;
@ -255,7 +255,7 @@ void onNewGPSData(void)
}
if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelD) {
posEstimator.gps.vel.z = - gpsSol.velNED[2]; // NEU
posEstimator.gps.vel.z = -gpsSol.velNED[Z]; // NEU
}
else {
posEstimator.gps.vel.z = (posEstimator.gps.vel.z + (gpsSol.llh.alt - previousAlt) / dT) / 2.0f;
@ -443,12 +443,10 @@ static void updateIMUTopic(timeUs_t currentTimeUs)
posEstimator.imu.accelNEU.z = 0;
}
#if defined(NAV_BLACKBOX)
/* Update blackbox values */
navAccNEU[X] = posEstimator.imu.accelNEU.x;
navAccNEU[Y] = posEstimator.imu.accelNEU.y;
navAccNEU[Z] = posEstimator.imu.accelNEU.z;
#endif
}
}
@ -785,10 +783,9 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs)
updateActualAltitudeAndClimbRate(false, posEstimator.est.pos.z, 0, posEstimator.est.aglAlt, 0, EST_NONE);
}
#if defined(NAV_BLACKBOX)
//Update Blackbox states
navEPH = posEstimator.est.eph;
navEPV = posEstimator.est.epv;
#endif
}
}

View file

@ -58,8 +58,8 @@ static timeUs_t crsfFrameStartAt = 0;
static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
// The power levels represented by uplinkTXPower above in mW (250mW added to full TX in v4.00 firmware)
const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000, 250};
// The power levels represented by uplinkTXPower above in mW (250mW added to full TX in v4.00 firmware, 50mW added for ExpressLRS)
const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000, 250, 50};
/*
* CRSF protocol

View file

@ -1,90 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#if defined(USE_RX_PPM)
#include "build/debug.h"
#include "common/utils.h"
#include "config/feature.h"
#include "drivers/timer.h"
#include "drivers/rx_pwm.h"
#include "drivers/time.h"
#include "fc/config.h"
#include "rx/rx.h"
#include "rx/pwm.h"
#define RC_PWM_50HZ_UPDATE (20 * 1000) // 50Hz update rate period
static uint16_t channelData[MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT];
static uint16_t readRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
{
UNUSED(rxRuntimeConfig);
return channelData[channel];
}
static uint8_t ppmFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
{
UNUSED(rxRuntimeConfig);
// PPM receiver counts received frames so we actually know if new data is available
if (isPPMDataBeingReceived()) {
for (int channel = 0; channel < MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT; channel++) {
channelData[channel] = ppmRead(channel);
}
resetPPMDataReceivedState();
return RX_FRAME_COMPLETE;
}
return RX_FRAME_PENDING;
}
bool rxPpmInit(rxRuntimeConfig_t *rxRuntimeConfig)
{
const timerHardware_t * timHw = timerGetByUsageFlag(TIM_USE_PPM);
if (timHw == NULL) {
return false;
}
if (!ppmInConfig(timHw)) {
return false;
}
rxRuntimeConfig->rxRefreshRate = RC_PWM_50HZ_UPDATE;
rxRuntimeConfig->requireFiltering = true;
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
rxRuntimeConfig->rcReadRawFn = readRawRC;
rxRuntimeConfig->rcFrameStatusFn = ppmFrameStatus;
return true;
}
#endif

View file

@ -1,20 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
bool rxPpmInit(rxRuntimeConfig_t *rxRuntimeConfig);

View file

@ -37,7 +37,6 @@
#include "drivers/adc.h"
#include "drivers/rx_pwm.h"
#include "drivers/rx_spi.h"
#include "drivers/serial.h"
#include "drivers/time.h"
@ -60,7 +59,6 @@
#include "rx/fport2.h"
#include "rx/msp.h"
#include "rx/msp_override.h"
#include "rx/pwm.h"
#include "rx/rx_spi.h"
#include "rx/sbus.h"
#include "rx/spektrum.h"
@ -110,7 +108,7 @@ rxLinkStatistics_t rxLinkStatistics;
rxRuntimeConfig_t rxRuntimeConfig;
static uint8_t rcSampleIndex = 0;
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 9);
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 10);
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
@ -285,7 +283,6 @@ void rxInit(void)
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rxRuntimeConfig.rxSignalTimeout = DELAY_10_HZ;
rxRuntimeConfig.requireFiltering = false;
rcSampleIndex = 0;
timeMs_t nowMs = millis();
@ -317,15 +314,6 @@ void rxInit(void)
}
switch (rxConfig()->receiverType) {
#if defined(USE_RX_PPM)
case RX_TYPE_PPM:
if (!rxPpmInit(&rxRuntimeConfig)) {
rxConfigMutable()->receiverType = RX_TYPE_NONE;
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
}
break;
#endif
#ifdef USE_SERIAL_RX
case RX_TYPE_SERIAL:
@ -477,39 +465,6 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
return result;
}
#define FILTERING_SAMPLE_COUNT 5
static uint16_t applyChannelFiltering(uint8_t chan, uint16_t sample)
{
static int16_t rcSamples[MAX_SUPPORTED_RC_CHANNEL_COUNT][FILTERING_SAMPLE_COUNT];
static bool rxSamplesCollected = false;
// Update the recent samples
rcSamples[chan][rcSampleIndex % FILTERING_SAMPLE_COUNT] = sample;
// Until we have enough data - return unfiltered samples
if (!rxSamplesCollected) {
if (rcSampleIndex < FILTERING_SAMPLE_COUNT) {
return sample;
}
rxSamplesCollected = true;
}
// Assuming a step transition from 1000 -> 2000 different filters will yield the following output:
// No filter: 1000, 2000, 2000, 2000, 2000 - 0 samples delay
// 3-point moving average: 1000, 1333, 1667, 2000, 2000 - 2 samples delay
// 3-point median: 1000, 1000, 2000, 2000, 2000 - 1 sample delay
// 5-point median: 1000, 1000, 1000, 2000, 2000 - 2 sample delay
// For the same filters - noise rejection capabilities (2 out of 5 outliers
// No filter: 1000, 2000, 1000, 2000, 1000, 1000, 1000
// 3-point MA: 1000, 1333, 1333, 1667, 1333, 1333, 1000 - noise has reduced magnitude, but spread over more samples
// 3-point median: 1000, 1000, 1000, 2000, 1000, 1000, 1000 - high density noise is not removed
// 5-point median: 1000, 1000, 1000, 1000, 1000, 1000, 1000 - only 3 out of 5 outlier noise will get through
// Apply 5-point median filtering. This filter has the same delay as 3-point moving average, but better noise rejection
return quickMedianFilter5_16(rcSamples[chan]);
}
bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
{
int16_t rcStaging[MAX_SUPPORTED_RC_CHANNEL_COUNT];
@ -576,14 +531,8 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
// Update channel input value if receiver is not in failsafe mode
// If receiver is in failsafe (not receiving signal or sending invalid channel values) - last good input values are retained
if (rxFlightChannelsValid && rxSignalReceived) {
if (rxRuntimeConfig.requireFiltering) {
for (int channel = 0; channel < rxChannelCount; channel++) {
rcChannels[channel].data = applyChannelFiltering(channel, rcStaging[channel]);
}
} else {
for (int channel = 0; channel < rxChannelCount; channel++) {
rcChannels[channel].data = rcStaging[channel];
}
for (int channel = 0; channel < rxChannelCount; channel++) {
rcChannels[channel].data = rcStaging[channel];
}
}

View file

@ -51,6 +51,8 @@
#define RSSI_MAX_VALUE 1023
#define PPM_RCVR_TIMEOUT 0
typedef enum {
RX_FRAME_PENDING = 0, // No new data available from receiver
RX_FRAME_COMPLETE = (1 << 0), // There is new data available
@ -61,11 +63,9 @@ typedef enum {
typedef enum {
RX_TYPE_NONE = 0,
RX_TYPE_PPM = 1,
RX_TYPE_SERIAL = 2,
RX_TYPE_MSP = 3,
RX_TYPE_SPI = 4,
RX_TYPE_UNUSED_1 = 5
RX_TYPE_SERIAL = 1,
RX_TYPE_MSP = 2,
RX_TYPE_SPI = 3
} rxReceiverType_e;
typedef enum {
@ -162,7 +162,6 @@ typedef struct rxRuntimeConfig_s {
uint8_t channelCount; // number of rc channels as reported by current input driver
timeUs_t rxRefreshRate;
timeUs_t rxSignalTimeout;
bool requireFiltering;
rcReadRawDataFnPtr rcReadRawFn;
rcFrameStatusFnPtr rcFrameStatusFn;
rcProcessFrameFnPtr rcProcessFrameFn;

View file

@ -52,6 +52,7 @@ FILE_COMPILE_FOR_SPEED
#include "drivers/accgyro/accgyro_bma280.h"
#include "drivers/accgyro/accgyro_bmi088.h"
#include "drivers/accgyro/accgyro_bmi160.h"
#include "drivers/accgyro/accgyro_bmi270.h"
#include "drivers/accgyro/accgyro_icm20689.h"
#include "drivers/accgyro/accgyro_icm42605.h"
#include "drivers/accgyro/accgyro_fake.h"
@ -282,6 +283,18 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
FALLTHROUGH;
#endif
#ifdef USE_IMU_BMI270
case ACC_BMI270:
if (bmi270AccDetect(dev)) {
accHardware = ACC_BMI270;
break;
}
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (accHardwareToUse != ACC_AUTODETECT) {
break;
}
FALLTHROUGH;
#endif
#ifdef USE_IMU_FAKE
case ACC_FAKE:

View file

@ -47,6 +47,7 @@ typedef enum {
ACC_ICM20689 = 11,
ACC_BMI088 = 12,
ACC_ICM42605 = 13,
ACC_BMI270 = 14,
ACC_FAKE,
ACC_MAX = ACC_FAKE
} accelerationSensor_e;

View file

@ -24,6 +24,7 @@
#include "sensors/rangefinder.h"
#include "sensors/pitotmeter.h"
#include "sensors/opflow.h"
#include "flight/secondary_imu.h"
extern uint8_t requestedSensors[SENSOR_INDEX_COUNT];
extern uint8_t detectedSensors[SENSOR_INDEX_COUNT];
@ -226,6 +227,7 @@ bool isHardwareHealthy(void)
const hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
const hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
const hardwareSensorStatus_e opflowStatus = getHwOpticalFlowStatus();
const hardwareSensorStatus_e imu2Status = getHwSecondaryImuStatus();
// Sensor is considered failing if it's either unavailable (selected but not detected) or unhealthy (returning invalid readings)
if (gyroStatus == HW_SENSOR_UNAVAILABLE || gyroStatus == HW_SENSOR_UNHEALTHY)
@ -252,5 +254,8 @@ bool isHardwareHealthy(void)
if (opflowStatus == HW_SENSOR_UNAVAILABLE || opflowStatus == HW_SENSOR_UNHEALTHY)
return false;
if (imu2Status == HW_SENSOR_UNAVAILABLE || opflowStatus == HW_SENSOR_UNHEALTHY)
return false;
return true;
}

View file

@ -5,6 +5,8 @@
* rather already known hardware status should be returned.
*/
#pragma once
typedef enum {
HW_SENSOR_NONE = 0, // Not selected
HW_SENSOR_OK = 1, // Selected, detected and healthy (ready to be used)

View file

@ -54,6 +54,7 @@ FILE_COMPILE_FOR_SPEED
#include "drivers/accgyro/accgyro_bma280.h"
#include "drivers/accgyro/accgyro_bmi088.h"
#include "drivers/accgyro/accgyro_bmi160.h"
#include "drivers/accgyro/accgyro_bmi270.h"
#include "drivers/accgyro/accgyro_icm20689.h"
#include "drivers/accgyro/accgyro_icm42605.h"
#include "drivers/accgyro/accgyro_fake.h"
@ -257,6 +258,15 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard
FALLTHROUGH;
#endif
#ifdef USE_IMU_BMI270
case GYRO_BMI270:
if (bmi270GyroDetect(dev)) {
gyroHardware = GYRO_BMI270;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_IMU_FAKE
case GYRO_FAKE:
if (fakeGyroDetect(dev)) {

View file

@ -38,6 +38,7 @@ typedef enum {
GYRO_ICM20689,
GYRO_BMI088,
GYRO_ICM42605,
GYRO_BMI270,
GYRO_FAKE
} gyroSensor_e;

View file

@ -38,10 +38,11 @@
#include "sensors/rangefinder.h"
#include "sensors/sensors.h"
#include "sensors/temperature.h"
#include "sensors/temperature.h"
#include "flight/secondary_imu.h"
uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_AUTODETECT, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE };
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE };
uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_AUTODETECT, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE, SECONDARY_IMU_NONE };
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE, SECONDARY_IMU_NONE };
bool sensorsAutodetect(void)
{

View file

@ -25,6 +25,7 @@ typedef enum {
SENSOR_INDEX_RANGEFINDER,
SENSOR_INDEX_PITOT,
SENSOR_INDEX_OPFLOW,
SENSOR_INDEX_IMU2,
SENSOR_INDEX_COUNT
} sensorIndex_e;

View file

@ -126,7 +126,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)

View file

@ -74,7 +74,6 @@
#define USE_UART2 // Receiver - RX (PA3)
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define AVOID_UART2_FOR_PWM_PPM
#define UART1_TX_PIN PB6
#define UART1_RX_PIN PB7

View file

@ -116,7 +116,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -142,10 +142,6 @@
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
// Disable PWM & PPM inputs
#undef USE_RX_PWM
#undef USE_RX_PPM
// Set default UARTs
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
#define SERIALRX_UART SERIAL_PORT_USART1

View file

@ -147,10 +147,6 @@
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
// Disable PWM & PPM inputs
#undef USE_RX_PWM
#undef USE_RX_PPM
// Set default UARTs
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
#define SERIALRX_UART SERIAL_PORT_USART1

View file

@ -131,7 +131,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View file

@ -134,7 +134,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_BLACKBOX)
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

View file

@ -56,7 +56,6 @@
#define USE_UART4
#define USE_UART5
#define SERIAL_PORT_COUNT 5
#define AVOID_UART2_FOR_PWM_PPM
#define UART1_TX_PIN PC4
#define UART1_RX_PIN PC5

View file

@ -29,9 +29,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS,
#endif
const timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2, 1, 6)
#if defined(FOXEERF722V2)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - D(2, 1, 6)
#else
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(2, 6, 0)
#endif
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(2, 6, 0)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(2, 7, 7)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(2, 4, 7)

View file

@ -91,9 +91,6 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#undef USE_RX_PWM
#undef USE_RX_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_TELEMETRY)
#define SERIALRX_PROVIDER SERIALRX_SBUS

View file

@ -130,7 +130,7 @@
#define USE_RANGEFINDER
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define USE_SPEKTRUM_BIND
// UART3,

View file

@ -76,8 +76,6 @@
#define MAX_PWM_OUTPUT_PORTS 12
#define AVOID_UART2_FOR_PWM_PPM
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff

View file

@ -134,7 +134,7 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define RX_CHANNELS_TAER
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)

View file

@ -94,7 +94,7 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
// Number of available PWM outputs

View file

@ -123,7 +123,7 @@
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_OSD)
#define BUTTONS

View file

@ -258,7 +258,7 @@
#define WS2811_PIN PA1
#endif
#define DEFAULT_RX_TYPE RX_TYPE_PPM
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)

View file

@ -73,7 +73,6 @@
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
//#define AVOID_UART2_FOR_PWM_PPM
#define USE_UART2
#define UART2_TX_PIN PA2 //not wired
#define UART2_RX_PIN PA3

Some files were not shown because too many files have changed in this diff Show more