mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 17:55:28 +03:00
Merge branch 'master' into abo_failsafe_emergency_landing
This commit is contained in:
commit
c81cf30d94
60 changed files with 542 additions and 769 deletions
|
@ -39,6 +39,7 @@ The stick positions are combined to activate different functions:
|
||||||
| Save setting | LOW | LOW | LOW | HIGH |
|
| Save setting | LOW | LOW | LOW | HIGH |
|
||||||
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
|
| 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/).
|
||||||

|

|
||||||
|
|
||||||
## Yaw control
|
## Yaw control
|
||||||
|
|
|
@ -1678,7 +1678,7 @@ _// TODO_
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 0 | 0 | 1 |
|
| 0 | 0 | 2 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1948,7 +1948,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 2500 | | 65535 |
|
| 1000 | | 65535 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
@ -1958,7 +1958,7 @@ Inertial Measurement Unit KP Gain for compass measurements
|
||||||
|
|
||||||
| Default | Min | Max |
|
| Default | Min | Max |
|
||||||
| --- | --- | --- |
|
| --- | --- | --- |
|
||||||
| 10000 | | 65535 |
|
| 5000 | | 65535 |
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
|
|
@ -138,3 +138,18 @@ appendWindowsPath=false
|
||||||
8. `cd build`
|
8. `cd build`
|
||||||
9. `cmake ..`
|
9. `cmake ..`
|
||||||
9. `make {TARGET}` should be working again
|
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.
|
||||||
|
|
|
@ -252,8 +252,6 @@ main_sources(COMMON_SRC
|
||||||
drivers/resource.h
|
drivers/resource.h
|
||||||
drivers/rcc.c
|
drivers/rcc.c
|
||||||
drivers/rcc.h
|
drivers/rcc.h
|
||||||
drivers/rx_pwm.c
|
|
||||||
drivers/rx_pwm.h
|
|
||||||
drivers/rx_spi.c
|
drivers/rx_spi.c
|
||||||
drivers/rx_spi.h
|
drivers/rx_spi.h
|
||||||
drivers/serial.c
|
drivers/serial.c
|
||||||
|
@ -416,8 +414,6 @@ main_sources(COMMON_SRC
|
||||||
rx/msp.h
|
rx/msp.h
|
||||||
rx/msp_override.c
|
rx/msp_override.c
|
||||||
rx/msp_override.h
|
rx/msp_override.h
|
||||||
rx/pwm.c
|
|
||||||
rx/pwm.h
|
|
||||||
rx/frsky_crc.c
|
rx/frsky_crc.c
|
||||||
rx/frsky_crc.h
|
rx/frsky_crc.h
|
||||||
rx/rx.c
|
rx/rx.c
|
||||||
|
|
|
@ -97,15 +97,30 @@
|
||||||
#define BLACKBOX_INVERTED_CARD_DETECTION 0
|
#define BLACKBOX_INVERTED_CARD_DETECTION 0
|
||||||
#endif
|
#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,
|
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
||||||
.device = DEFAULT_BLACKBOX_DEVICE,
|
.device = DEFAULT_BLACKBOX_DEVICE,
|
||||||
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
|
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
|
||||||
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
|
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
|
||||||
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
|
.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
|
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
|
||||||
static const int32_t blackboxSInterval = 4096;
|
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", 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", 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)},
|
{"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)},
|
{"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)},
|
{"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", 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", 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)},
|
{"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", 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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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", 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", 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},
|
{"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", 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)},
|
{"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)},
|
{"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)},
|
{"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)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"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), CONDITION(ALWAYS)},
|
{"navVel", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .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), CONDITION(ALWAYS)},
|
{"navTgtVel", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
|
||||||
{"navAcc", 1, 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), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
|
||||||
{"navAcc", 2, 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), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
|
||||||
{"navTgtVel", 0, 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), FLIGHT_LOG_FIELD_CONDITION_NAV_POS},
|
||||||
{"navTgtVel", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
{"navTgtPos", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .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), CONDITION(ALWAYS)},
|
{"navTgtPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .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), CONDITION(ALWAYS)},
|
{"navSurf", -1, 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), CONDITION(ALWAYS)},
|
{"navAcc", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
|
||||||
{"navTgtPos", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
{"navAcc", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
|
||||||
{"navSurf", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
{"navAcc", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_NAV_ACC},
|
||||||
#endif
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef USE_GPS
|
#ifdef USE_GPS
|
||||||
|
@ -422,6 +438,7 @@ typedef struct blackboxMainState_s {
|
||||||
int32_t axisPID_P[XYZ_AXIS_COUNT];
|
int32_t axisPID_P[XYZ_AXIS_COUNT];
|
||||||
int32_t axisPID_I[XYZ_AXIS_COUNT];
|
int32_t axisPID_I[XYZ_AXIS_COUNT];
|
||||||
int32_t axisPID_D[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 axisPID_Setpoint[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
int32_t mcPosAxisP[XYZ_AXIS_COUNT];
|
int32_t mcPosAxisP[XYZ_AXIS_COUNT];
|
||||||
|
@ -461,7 +478,6 @@ typedef struct blackboxMainState_s {
|
||||||
int32_t surfaceRaw;
|
int32_t surfaceRaw;
|
||||||
#endif
|
#endif
|
||||||
uint16_t rssi;
|
uint16_t rssi;
|
||||||
#ifdef NAV_BLACKBOX
|
|
||||||
int16_t navState;
|
int16_t navState;
|
||||||
uint16_t navFlags;
|
uint16_t navFlags;
|
||||||
uint16_t navEPH;
|
uint16_t navEPH;
|
||||||
|
@ -474,7 +490,6 @@ typedef struct blackboxMainState_s {
|
||||||
int16_t navHeading;
|
int16_t navHeading;
|
||||||
int16_t navTargetHeading;
|
int16_t navTargetHeading;
|
||||||
int16_t navSurface;
|
int16_t navSurface;
|
||||||
#endif
|
|
||||||
} blackboxMainState_t;
|
} blackboxMainState_t;
|
||||||
|
|
||||||
typedef struct blackboxGpsState_s {
|
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_1:
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
|
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
|
||||||
// D output can be set by either the D or the FF term
|
// 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:
|
case FLIGHT_LOG_FIELD_CONDITION_MAG:
|
||||||
#ifdef USE_MAG
|
#ifdef USE_MAG
|
||||||
return sensors(SENSOR_MAG);
|
return sensors(SENSOR_MAG) && blackboxIncludeFlag(BLACKBOX_FEATURE_MAG);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
@ -634,14 +649,14 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV:
|
case FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV:
|
||||||
#ifdef USE_NAV
|
#ifdef USE_NAV
|
||||||
return STATE(FIXED_WING_LEGACY);
|
return STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_MC_NAV:
|
case FLIGHT_LOG_FIELD_CONDITION_MC_NAV:
|
||||||
#ifdef USE_NAV
|
#ifdef USE_NAV
|
||||||
return !STATE(FIXED_WING_LEGACY);
|
return !STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
@ -657,9 +672,22 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
||||||
case FLIGHT_LOG_FIELD_CONDITION_DEBUG:
|
case FLIGHT_LOG_FIELD_CONDITION_DEBUG:
|
||||||
return debugMode != DEBUG_NONE;
|
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:
|
case FLIGHT_LOG_FIELD_CONDITION_NEVER:
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -733,6 +761,7 @@ static void writeIntraframe(void)
|
||||||
blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x]);
|
blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
blackboxWriteSignedVBArray(blackboxCurrent->axisPID_F, XYZ_AXIS_COUNT);
|
||||||
|
|
||||||
if (testBlackboxCondition(CONDITION(FIXED_WING_NAV))) {
|
if (testBlackboxCondition(CONDITION(FIXED_WING_NAV))) {
|
||||||
blackboxWriteSignedVBArray(blackboxCurrent->fwAltPID, 3);
|
blackboxWriteSignedVBArray(blackboxCurrent->fwAltPID, 3);
|
||||||
|
@ -811,8 +840,14 @@ static void writeIntraframe(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
|
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)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
|
||||||
blackboxWriteSignedVBArray(blackboxCurrent->debug, DEBUG32_VALUE_COUNT);
|
blackboxWriteSignedVBArray(blackboxCurrent->debug, DEBUG32_VALUE_COUNT);
|
||||||
|
@ -834,36 +869,41 @@ static void writeIntraframe(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef NAV_BLACKBOX
|
|
||||||
blackboxWriteSignedVB(blackboxCurrent->navState);
|
blackboxWriteSignedVB(blackboxCurrent->navState);
|
||||||
|
|
||||||
blackboxWriteSignedVB(blackboxCurrent->navFlags);
|
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++) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_ACC)) {
|
||||||
blackboxWriteSignedVB(blackboxCurrent->navRealVel[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->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:
|
//Rotate our history buffers:
|
||||||
|
|
||||||
//The current state becomes the new "before" state
|
//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))) {
|
if (testBlackboxCondition(CONDITION(FIXED_WING_NAV))) {
|
||||||
|
|
||||||
arraySubInt32(deltas, blackboxCurrent->fwAltPID, blackboxLast->fwAltPID, 3);
|
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:
|
//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, 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)) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
|
||||||
blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
|
blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
|
||||||
}
|
}
|
||||||
|
@ -1050,36 +1100,43 @@ static void writeInterframe(void)
|
||||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
|
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef NAV_BLACKBOX
|
|
||||||
blackboxWriteSignedVB(blackboxCurrent->navState - blackboxLast->navState);
|
blackboxWriteSignedVB(blackboxCurrent->navState - blackboxLast->navState);
|
||||||
|
|
||||||
blackboxWriteSignedVB(blackboxCurrent->navFlags - blackboxLast->navFlags);
|
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++) {
|
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NAV_ACC)) {
|
||||||
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]->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
|
//Rotate our history buffers
|
||||||
blackboxHistory[2] = blackboxHistory[1];
|
blackboxHistory[2] = blackboxHistory[1];
|
||||||
blackboxHistory[1] = blackboxHistory[0];
|
blackboxHistory[1] = blackboxHistory[0];
|
||||||
|
@ -1396,6 +1453,7 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
blackboxCurrent->axisPID_P[i] = axisPID_P[i];
|
blackboxCurrent->axisPID_P[i] = axisPID_P[i];
|
||||||
blackboxCurrent->axisPID_I[i] = axisPID_I[i];
|
blackboxCurrent->axisPID_I[i] = axisPID_I[i];
|
||||||
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
|
blackboxCurrent->axisPID_D[i] = axisPID_D[i];
|
||||||
|
blackboxCurrent->axisPID_F[i] = axisPID_F[i];
|
||||||
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
|
blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
|
||||||
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
|
blackboxCurrent->accADC[i] = lrintf(acc.accADCf[i] * acc.dev.acc_1G);
|
||||||
#ifdef USE_MAG
|
#ifdef USE_MAG
|
||||||
|
@ -1479,7 +1537,6 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
blackboxCurrent->servo[i] = servo[i];
|
blackboxCurrent->servo[i] = servo[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef NAV_BLACKBOX
|
|
||||||
blackboxCurrent->navState = navCurrentState;
|
blackboxCurrent->navState = navCurrentState;
|
||||||
blackboxCurrent->navFlags = navFlags;
|
blackboxCurrent->navFlags = navFlags;
|
||||||
blackboxCurrent->navEPH = navEPH;
|
blackboxCurrent->navEPH = navEPH;
|
||||||
|
@ -1492,7 +1549,6 @@ static void loadMainState(timeUs_t currentTimeUs)
|
||||||
blackboxCurrent->navTargetPos[i] = navTargetPosition[i];
|
blackboxCurrent->navTargetPos[i] = navTargetPosition[i];
|
||||||
}
|
}
|
||||||
blackboxCurrent->navSurface = navActualSurface;
|
blackboxCurrent->navSurface = navActualSurface;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1690,15 +1746,18 @@ static bool blackboxWriteSysinfo(void)
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->stabilized.rates[ROLL],
|
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->stabilized.rates[ROLL],
|
||||||
currentControlRateProfile->stabilized.rates[PITCH],
|
currentControlRateProfile->stabilized.rates[PITCH],
|
||||||
currentControlRateProfile->stabilized.rates[YAW]);
|
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].I,
|
||||||
pidBank()->pid[PID_ROLL].D);
|
pidBank()->pid[PID_ROLL].D,
|
||||||
BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", pidBank()->pid[PID_PITCH].P,
|
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].I,
|
||||||
pidBank()->pid[PID_PITCH].D);
|
pidBank()->pid[PID_PITCH].D,
|
||||||
BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", pidBank()->pid[PID_YAW].P,
|
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].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,
|
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].I,
|
||||||
pidBank()->pid[PID_POS_Z].D);
|
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("motor_pwm_rate", "%d", motorConfig()->motorPwmRate);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
|
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
||||||
#ifdef NAV_BLACKBOX
|
|
||||||
BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid());
|
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_hz", "%d", accelerometerConfig()->acc_notch_hz);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
|
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);
|
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);
|
||||||
|
|
|
@ -21,11 +21,22 @@
|
||||||
|
|
||||||
#include "config/parameter_group.h"
|
#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 {
|
typedef struct blackboxConfig_s {
|
||||||
uint16_t rate_num;
|
uint16_t rate_num;
|
||||||
uint16_t rate_denom;
|
uint16_t rate_denom;
|
||||||
uint8_t device;
|
uint8_t device;
|
||||||
uint8_t invertedCardDetection;
|
uint8_t invertedCardDetection;
|
||||||
|
uint32_t includeFlags;
|
||||||
} blackboxConfig_t;
|
} blackboxConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(blackboxConfig_t, blackboxConfig);
|
PG_DECLARE(blackboxConfig_t, blackboxConfig);
|
||||||
|
@ -37,3 +48,6 @@ void blackboxUpdate(timeUs_t currentTimeUs);
|
||||||
void blackboxStart(void);
|
void blackboxStart(void);
|
||||||
void blackboxFinish(void);
|
void blackboxFinish(void);
|
||||||
bool blackboxMayEditConfig(void);
|
bool blackboxMayEditConfig(void);
|
||||||
|
void blackboxIncludeFlagSet(uint32_t mask);
|
||||||
|
void blackboxIncludeFlagClear(uint32_t mask);
|
||||||
|
bool blackboxIncludeFlag(uint32_t mask);
|
|
@ -52,6 +52,12 @@ typedef enum FlightLogFieldCondition {
|
||||||
|
|
||||||
FLIGHT_LOG_FIELD_CONDITION_DEBUG,
|
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_NEVER,
|
||||||
|
|
||||||
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
|
FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
|
||||||
|
|
|
@ -72,7 +72,6 @@ typedef enum {
|
||||||
DEBUG_DYNAMIC_FILTER,
|
DEBUG_DYNAMIC_FILTER,
|
||||||
DEBUG_DYNAMIC_FILTER_FREQUENCY,
|
DEBUG_DYNAMIC_FILTER_FREQUENCY,
|
||||||
DEBUG_IRLOCK,
|
DEBUG_IRLOCK,
|
||||||
DEBUG_CD,
|
|
||||||
DEBUG_KALMAN_GAIN,
|
DEBUG_KALMAN_GAIN,
|
||||||
DEBUG_PID_MEASUREMENT,
|
DEBUG_PID_MEASUREMENT,
|
||||||
DEBUG_SPM_CELLS, // Smartport master FLVSS
|
DEBUG_SPM_CELLS, // Smartport master FLVSS
|
||||||
|
@ -81,7 +80,6 @@ typedef enum {
|
||||||
DEBUG_PCF8574,
|
DEBUG_PCF8574,
|
||||||
DEBUG_DYNAMIC_GYRO_LPF,
|
DEBUG_DYNAMIC_GYRO_LPF,
|
||||||
DEBUG_AUTOLEVEL,
|
DEBUG_AUTOLEVEL,
|
||||||
DEBUG_FW_D,
|
|
||||||
DEBUG_IMU2,
|
DEBUG_IMU2,
|
||||||
DEBUG_ALTITUDE,
|
DEBUG_ALTITUDE,
|
||||||
DEBUG_GYRO_ALPHA_BETA_GAMMA,
|
DEBUG_GYRO_ALPHA_BETA_GAMMA,
|
||||||
|
|
|
@ -24,8 +24,6 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
|
|
||||||
#include "drivers/rx_pwm.h"
|
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "flight/servos.h"
|
#include "flight/servos.h"
|
||||||
|
|
|
@ -56,6 +56,7 @@
|
||||||
#define SYM_AH_MI 0x24 // 036 Ah/mi
|
#define SYM_AH_MI 0x24 // 036 Ah/mi
|
||||||
// 0x25 // 037 ASCII %
|
// 0x25 // 037 ASCII %
|
||||||
// 0x26 // 038 ASCII &
|
// 0x26 // 038 ASCII &
|
||||||
|
#define SYM_VTX_POWER 0x27 // 039 VTx Power
|
||||||
// 0x28 // 040 to 062 ASCII
|
// 0x28 // 040 to 062 ASCII
|
||||||
#define SYM_AH_NM 0x3F // 063 Ah/NM
|
#define SYM_AH_NM 0x3F // 063 Ah/NM
|
||||||
// 0x40 // 064 to 095 ASCII
|
// 0x40 // 064 to 095 ASCII
|
||||||
|
@ -158,6 +159,7 @@
|
||||||
#define SYM_HEADING_W 0xCB // 203 Heading Graphic west
|
#define SYM_HEADING_W 0xCB // 203 Heading Graphic west
|
||||||
#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic
|
#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic
|
||||||
#define SYM_HEADING_LINE 0xCD // 205 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_START 0x101 // 257 to 280, INAV logo
|
||||||
|
|
|
@ -36,7 +36,6 @@
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
//#include "drivers/rx_pwm.h"
|
|
||||||
|
|
||||||
#include "sensors/rangefinder.h"
|
#include "sensors/rangefinder.h"
|
||||||
|
|
||||||
|
|
|
@ -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
|
|
|
@ -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);
|
|
|
@ -60,7 +60,6 @@ uint8_t cliMode = 0;
|
||||||
#include "drivers/io_impl.h"
|
#include "drivers/io_impl.h"
|
||||||
#include "drivers/osd_symbols.h"
|
#include "drivers/osd_symbols.h"
|
||||||
#include "drivers/persistent.h"
|
#include "drivers/persistent.h"
|
||||||
#include "drivers/rx_pwm.h"
|
|
||||||
#include "drivers/sdcard/sdcard.h"
|
#include "drivers/sdcard/sdcard.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
@ -162,6 +161,12 @@ static const char * const featureNames[] = {
|
||||||
"OSD", "FW_LAUNCH", "FW_AUTOTRIM", NULL
|
"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) */
|
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
||||||
// sync with gyroSensor_e
|
// sync with gyroSensor_e
|
||||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"};
|
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"};
|
||||||
|
@ -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)
|
#if defined(BEEPER) || defined(USE_DSHOT)
|
||||||
static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
|
static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
|
||||||
{
|
{
|
||||||
|
@ -3505,6 +3598,11 @@ static void printConfig(const char *cmdline, bool doDiff)
|
||||||
printBeeper(dumpMask, &beeperConfig_Copy, beeperConfig());
|
printBeeper(dumpMask, &beeperConfig_Copy, beeperConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_BLACKBOX
|
||||||
|
cliPrintHashLine("blackbox");
|
||||||
|
printBlackbox(dumpMask, &blackboxConfig_Copy, blackboxConfig());
|
||||||
|
#endif
|
||||||
|
|
||||||
cliPrintHashLine("map");
|
cliPrintHashLine("map");
|
||||||
printMap(dumpMask, &rxConfig_Copy, rxConfig());
|
printMap(dumpMask, &rxConfig_Copy, rxConfig());
|
||||||
|
|
||||||
|
@ -3698,6 +3796,11 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("feature", "configure features",
|
CLI_COMMAND_DEF("feature", "configure features",
|
||||||
"list\r\n"
|
"list\r\n"
|
||||||
"\t<+|->[name]", cliFeature),
|
"\t<+|->[name]", cliFeature),
|
||||||
|
#ifdef USE_BLACKBOX
|
||||||
|
CLI_COMMAND_DEF("blackbox", "configure blackbox fields",
|
||||||
|
"list\r\n"
|
||||||
|
"\t<+|->[name]", cliBlackbox),
|
||||||
|
#endif
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
|
CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
|
||||||
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
|
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
|
||||||
|
|
|
@ -107,7 +107,7 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||||
.enabledFeatures = DEFAULT_FEATURES | COMMON_DEFAULT_FEATURES
|
.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,
|
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
.current_profile_index = 0,
|
.current_profile_index = 0,
|
||||||
|
@ -193,13 +193,6 @@ void validateAndFixConfig(void)
|
||||||
// Disable unused features
|
// 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);
|
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 defined(USE_LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||||
if (featureConfigured(FEATURE_SOFTSERIAL) && featureConfigured(FEATURE_LED_STRIP)) {
|
if (featureConfigured(FEATURE_SOFTSERIAL) && featureConfigured(FEATURE_LED_STRIP)) {
|
||||||
const timerHardware_t *ledTimerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
const timerHardware_t *ledTimerHardware = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/rx_pwm.h"
|
|
||||||
#include "fc/stats.h"
|
#include "fc/stats.h"
|
||||||
|
|
||||||
#define MAX_PROFILE_COUNT 3
|
#define MAX_PROFILE_COUNT 3
|
||||||
|
@ -30,7 +29,7 @@
|
||||||
#define MAX_NAME_LENGTH 16
|
#define MAX_NAME_LENGTH 16
|
||||||
|
|
||||||
#define TASK_GYRO_LOOPTIME 250 // Task gyro always runs at 4kHz
|
#define TASK_GYRO_LOOPTIME 250 // Task gyro always runs at 4kHz
|
||||||
typedef enum {
|
typedef enum {
|
||||||
FEATURE_THR_VBAT_COMP = 1 << 0,
|
FEATURE_THR_VBAT_COMP = 1 << 0,
|
||||||
FEATURE_VBAT = 1 << 1,
|
FEATURE_VBAT = 1 << 1,
|
||||||
FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command
|
FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command
|
||||||
|
|
|
@ -63,7 +63,6 @@
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/rx_pwm.h"
|
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
|
@ -277,15 +276,7 @@ void init(void)
|
||||||
|
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
|
||||||
#if defined(AVOID_UART2_FOR_PWM_PPM)
|
serialInit(feature(FEATURE_SOFTSERIAL));
|
||||||
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
|
|
||||||
|
|
||||||
// Initialize MSP serial ports here so LOG can share a port with MSP.
|
// 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
|
// XXX: Don't call mspFcInit() yet, since it initializes the boxes and needs
|
||||||
|
|
|
@ -25,7 +25,7 @@ tables:
|
||||||
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
|
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
|
||||||
enum: pitotSensor_e
|
enum: pitotSensor_e
|
||||||
- name: receiver_type
|
- name: receiver_type
|
||||||
values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UNUSED"]
|
values: ["NONE", "SERIAL", "MSP", "SPI"]
|
||||||
enum: rxReceiverType_e
|
enum: rxReceiverType_e
|
||||||
- name: serial_rx
|
- name: serial_rx
|
||||||
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
|
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
|
||||||
|
@ -93,7 +93,7 @@ tables:
|
||||||
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
|
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
|
||||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
||||||
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
|
"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"]
|
"GYRO_ALPHA_BETA_GAMMA", "SMITH_PREDICTOR", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS"]
|
||||||
- name: async_mode
|
- name: async_mode
|
||||||
values: ["NONE", "GYRO", "ALL"]
|
values: ["NONE", "GYRO", "ALL"]
|
||||||
|
@ -307,7 +307,7 @@ groups:
|
||||||
- name: gyro_to_use
|
- name: gyro_to_use
|
||||||
condition: USE_DUAL_GYRO
|
condition: USE_DUAL_GYRO
|
||||||
min: 0
|
min: 0
|
||||||
max: 1
|
max: 2
|
||||||
default_value: 0
|
default_value: 0
|
||||||
- name: gyro_abg_alpha
|
- name: gyro_abg_alpha
|
||||||
description: "Alpha factor for Gyro Alpha-Beta-Gamma filter"
|
description: "Alpha factor for Gyro Alpha-Beta-Gamma filter"
|
||||||
|
@ -1493,7 +1493,7 @@ groups:
|
||||||
members:
|
members:
|
||||||
- name: imu_dcm_kp
|
- name: imu_dcm_kp
|
||||||
description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
|
description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
|
||||||
default_value: 2500
|
default_value: 1000
|
||||||
field: dcm_kp_acc
|
field: dcm_kp_acc
|
||||||
max: UINT16_MAX
|
max: UINT16_MAX
|
||||||
- name: imu_dcm_ki
|
- name: imu_dcm_ki
|
||||||
|
@ -1503,7 +1503,7 @@ groups:
|
||||||
max: UINT16_MAX
|
max: UINT16_MAX
|
||||||
- name: imu_dcm_kp_mag
|
- name: imu_dcm_kp_mag
|
||||||
description: "Inertial Measurement Unit KP Gain for compass measurements"
|
description: "Inertial Measurement Unit KP Gain for compass measurements"
|
||||||
default_value: 10000
|
default_value: 5000
|
||||||
field: dcm_kp_mag
|
field: dcm_kp_mag
|
||||||
max: UINT16_MAX
|
max: UINT16_MAX
|
||||||
- name: imu_dcm_ki_mag
|
- name: imu_dcm_ki_mag
|
||||||
|
|
|
@ -107,7 +107,7 @@ typedef struct {
|
||||||
bool itermLimitActive;
|
bool itermLimitActive;
|
||||||
bool itermFreezeActive;
|
bool itermFreezeActive;
|
||||||
|
|
||||||
pt2Filter_t rateTargetFilter;
|
pt3Filter_t rateTargetFilter;
|
||||||
|
|
||||||
smithPredictor_t smithPredictor;
|
smithPredictor_t smithPredictor;
|
||||||
} pidState_t;
|
} pidState_t;
|
||||||
|
@ -123,7 +123,11 @@ STATIC_FASTRAM bool pidGainsUpdateRequired;
|
||||||
FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT];
|
FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||||
|
|
||||||
#ifdef USE_BLACKBOX
|
#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
|
#endif
|
||||||
|
|
||||||
static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
|
static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||||
|
@ -339,7 +343,7 @@ bool pidInitFilters(void)
|
||||||
|
|
||||||
if (pidProfile()->controlDerivativeLpfHz) {
|
if (pidProfile()->controlDerivativeLpfHz) {
|
||||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
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].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].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].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;
|
pidState[axis].kFF = 0.0f;
|
||||||
|
|
||||||
// Tracking anti-windup requires P/I/D to be all defined which is only true for MC
|
// 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 newDTerm = dTermProcess(pidState, dT);
|
||||||
const float newFFTerm = pidState->rateTarget * pidState->kFF;
|
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
|
* 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_P[axis] = newPTerm;
|
||||||
axisPID_I[axis] = pidState->errorGyroIf;
|
axisPID_I[axis] = pidState->errorGyroIf;
|
||||||
axisPID_D[axis] = newDTerm;
|
axisPID_D[axis] = newDTerm;
|
||||||
|
axisPID_F[axis] = newFFTerm;
|
||||||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -803,13 +807,12 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
|
||||||
const float newDTerm = dTermProcess(pidState, dT);
|
const float newDTerm = dTermProcess(pidState, dT);
|
||||||
|
|
||||||
const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget;
|
const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget;
|
||||||
const float rateTargetDeltaFiltered = pt2FilterApply(&pidState->rateTargetFilter, rateTargetDelta);
|
const float rateTargetDeltaFiltered = pt3FilterApply(&pidState->rateTargetFilter, rateTargetDelta);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Compute Control Derivative
|
* Compute Control Derivative
|
||||||
*/
|
*/
|
||||||
const float newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT);
|
const float newCDTerm = rateTargetDeltaFiltered * pidState->kCD;
|
||||||
DEBUG_SET(DEBUG_CD, axis, newCDTerm);
|
|
||||||
|
|
||||||
// TODO: Get feedback from mixer on available correction range for each axis
|
// TODO: Get feedback from mixer on available correction range for each axis
|
||||||
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm;
|
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_P[axis] = newPTerm;
|
||||||
axisPID_I[axis] = pidState->errorGyroIf;
|
axisPID_I[axis] = pidState->errorGyroIf;
|
||||||
axisPID_D[axis] = newDTerm;
|
axisPID_D[axis] = newDTerm;
|
||||||
|
axisPID_F[axis] = newCDTerm;
|
||||||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -189,7 +189,7 @@ const pidBank_t * pidBank(void);
|
||||||
pidBank_t * pidBankMutable(void);
|
pidBank_t * pidBankMutable(void);
|
||||||
|
|
||||||
extern int16_t axisPID[];
|
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);
|
void pidInit(void);
|
||||||
bool pidInitFilters(void);
|
bool pidInitFilters(void);
|
||||||
|
|
|
@ -156,6 +156,8 @@ static float GForce, GForceAxis[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
typedef struct statistic_s {
|
typedef struct statistic_s {
|
||||||
uint16_t max_speed;
|
uint16_t max_speed;
|
||||||
|
uint16_t max_3D_speed;
|
||||||
|
uint16_t max_air_speed;
|
||||||
uint16_t min_voltage; // /100
|
uint16_t min_voltage; // /100
|
||||||
int16_t max_current;
|
int16_t max_current;
|
||||||
int32_t max_power;
|
int32_t max_power;
|
||||||
|
@ -421,7 +423,7 @@ static int32_t osdConvertVelocityToUnit(int32_t vel)
|
||||||
* Converts velocity into a string based on the current unit system.
|
* 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)
|
* @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) {
|
switch ((osd_unit_e)osdConfig()->units) {
|
||||||
case OSD_UNIT_UK:
|
case OSD_UNIT_UK:
|
||||||
|
@ -429,13 +431,25 @@ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D)
|
||||||
case OSD_UNIT_METRIC_MPH:
|
case OSD_UNIT_METRIC_MPH:
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case OSD_UNIT_IMPERIAL:
|
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;
|
break;
|
||||||
case OSD_UNIT_METRIC:
|
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;
|
break;
|
||||||
case OSD_UNIT_GA:
|
case OSD_UNIT_GA:
|
||||||
tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT));
|
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;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1569,14 +1583,20 @@ static bool osdDrawSingleElement(uint8_t item)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_GPS_SPEED:
|
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;
|
break;
|
||||||
|
|
||||||
case OSD_3D_SPEED:
|
case OSD_3D_SPEED:
|
||||||
{
|
osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false);
|
||||||
osdFormatVelocityStr(buff, osdGet3DSpeed(), true);
|
break;
|
||||||
break;
|
|
||||||
}
|
case OSD_3D_MAX_SPEED:
|
||||||
|
osdFormatVelocityStr(buff, stats.max_3D_speed, true, true);
|
||||||
|
break;
|
||||||
|
|
||||||
case OSD_GLIDESLOPE:
|
case OSD_GLIDESLOPE:
|
||||||
{
|
{
|
||||||
|
@ -1965,9 +1985,12 @@ static bool osdDrawSingleElement(uint8_t item)
|
||||||
vtxDeviceOsdInfo_t osdInfo;
|
vtxDeviceOsdInfo_t osdInfo;
|
||||||
vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo);
|
vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo);
|
||||||
|
|
||||||
|
tfp_sprintf(buff, "%c", SYM_VTX_POWER);
|
||||||
|
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
||||||
|
|
||||||
tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter);
|
tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter);
|
||||||
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||||
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
|
displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2406,7 +2429,19 @@ static bool osdDrawSingleElement(uint8_t item)
|
||||||
{
|
{
|
||||||
#ifdef USE_PITOT
|
#ifdef USE_PITOT
|
||||||
buff[0] = SYM_AIR;
|
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
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
@ -3434,6 +3469,8 @@ static void osdResetStats(void)
|
||||||
stats.max_current = 0;
|
stats.max_current = 0;
|
||||||
stats.max_power = 0;
|
stats.max_power = 0;
|
||||||
stats.max_speed = 0;
|
stats.max_speed = 0;
|
||||||
|
stats.max_3D_speed = 0;
|
||||||
|
stats.max_air_speed = 0;
|
||||||
stats.min_voltage = 5000;
|
stats.min_voltage = 5000;
|
||||||
stats.min_rssi = 99;
|
stats.min_rssi = 99;
|
||||||
stats.min_lq = 300;
|
stats.min_lq = 300;
|
||||||
|
@ -3447,8 +3484,14 @@ static void osdUpdateStats(void)
|
||||||
|
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
value = osdGet3DSpeed();
|
value = osdGet3DSpeed();
|
||||||
if (stats.max_speed < value)
|
if (stats.max_3D_speed < value)
|
||||||
stats.max_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)
|
if (stats.max_distance < GPS_distanceToHome)
|
||||||
stats.max_distance = GPS_distanceToHome;
|
stats.max_distance = GPS_distanceToHome;
|
||||||
|
@ -3497,7 +3540,7 @@ static void osdShowStatsPage1(void)
|
||||||
|
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :");
|
displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :");
|
||||||
osdFormatVelocityStr(buff, stats.max_speed, true);
|
osdFormatVelocityStr(buff, stats.max_3D_speed, true, false);
|
||||||
osdLeftAlignString(buff);
|
osdLeftAlignString(buff);
|
||||||
displayWrite(osdDisplayPort, statValuesX, top++, buff);
|
displayWrite(osdDisplayPort, statValuesX, top++, buff);
|
||||||
|
|
||||||
|
@ -4033,82 +4076,60 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
|
||||||
// messages to show.
|
// messages to show.
|
||||||
const char *messages[5];
|
const char *messages[5];
|
||||||
unsigned messageCount = 0;
|
unsigned messageCount = 0;
|
||||||
if (FLIGHT_MODE(FAILSAFE_MODE)) {
|
const char *failsafeInfoMessage = NULL;
|
||||||
// In FS mode while being armed too
|
|
||||||
const char *failsafePhaseMessage = osdFailsafePhaseMessage();
|
|
||||||
const char *failsafeInfoMessage = osdFailsafeInfoMessage();
|
|
||||||
const char *navStateFSMessage = navigationStateMessage();
|
|
||||||
|
|
||||||
if (failsafePhaseMessage) {
|
if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
|
||||||
messages[messageCount++] = failsafePhaseMessage;
|
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) {
|
if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) {
|
||||||
messages[messageCount++] = failsafeInfoMessage;
|
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED);
|
||||||
}
|
} else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) {
|
||||||
if (navStateFSMessage) {
|
// Countdown display for remaining Waypoints
|
||||||
messages[messageCount++] = navStateFSMessage;
|
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)
|
#if defined(USE_SAFE_HOME)
|
||||||
const char *safehomeMessage = divertingToSafehomeMessage();
|
const char *safehomeMessage = divertingToSafehomeMessage();
|
||||||
if (safehomeMessage) {
|
if (safehomeMessage) {
|
||||||
messages[messageCount++] = 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.
|
|
||||||
}
|
}
|
||||||
} 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
|
#endif
|
||||||
} else if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) {
|
if (FLIGHT_MODE(FAILSAFE_MODE)) {
|
||||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH);
|
// In FS mode while being armed too
|
||||||
const char *launchStateMessage = fixedWingLaunchStateMessage();
|
const char *failsafePhaseMessage = osdFailsafePhaseMessage();
|
||||||
if (launchStateMessage) {
|
failsafeInfoMessage = osdFailsafeInfoMessage();
|
||||||
messages[messageCount++] = launchStateMessage;
|
|
||||||
}
|
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 {
|
} else {
|
||||||
if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) {
|
if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) {
|
||||||
// ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO
|
// ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO
|
||||||
|
@ -4130,11 +4151,20 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
|
||||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE);
|
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Pick one of the available messages. Each message lasts
|
}
|
||||||
// a second.
|
if (messageCount > 0) {
|
||||||
if (messageCount > 0) {
|
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)];
|
||||||
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)) {
|
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {
|
||||||
unsigned invalidIndex;
|
unsigned invalidIndex;
|
||||||
|
|
|
@ -231,6 +231,9 @@ typedef enum {
|
||||||
OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
|
OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
|
||||||
OSD_PLIMIT_ACTIVE_POWER_LIMIT,
|
OSD_PLIMIT_ACTIVE_POWER_LIMIT,
|
||||||
OSD_GLIDESLOPE,
|
OSD_GLIDESLOPE,
|
||||||
|
OSD_GPS_MAX_SPEED,
|
||||||
|
OSD_3D_MAX_SPEED,
|
||||||
|
OSD_AIR_MAX_SPEED,
|
||||||
OSD_ITEM_COUNT // MUST BE LAST
|
OSD_ITEM_COUNT // MUST BE LAST
|
||||||
} osd_items_e;
|
} osd_items_e;
|
||||||
|
|
||||||
|
@ -412,7 +415,7 @@ int32_t osdGetAltitude(void);
|
||||||
void osdCrosshairPosition(uint8_t *x, uint8_t *y);
|
void osdCrosshairPosition(uint8_t *x, uint8_t *y);
|
||||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length);
|
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length);
|
||||||
void osdFormatAltitudeSymbol(char *buff, int32_t alt);
|
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).
|
// Returns a heading angle in degrees normalized to [0, 360).
|
||||||
int osdGetHeadingAngle(int angle);
|
int osdGetHeadingAngle(int angle);
|
||||||
|
|
||||||
|
|
|
@ -351,7 +351,7 @@ void osdHudDrawExtras(uint8_t poi_id)
|
||||||
|
|
||||||
displayWrite(osdGetDisplayPort(), minX + 4, lineY, buftmp);
|
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);
|
displayWrite(osdGetDisplayPort(), maxX - 9, lineY, buftmp);
|
||||||
|
|
||||||
tfp_sprintf(buftmp, "%3d%c", radar_pois[poi_id].heading, SYM_HEADING);
|
tfp_sprintf(buftmp, "%3d%c", radar_pois[poi_id].heading, SYM_HEADING);
|
||||||
|
|
|
@ -441,7 +441,7 @@ void closeSerialPort(serialPort_t *serialPort)
|
||||||
serialPortUsage->serialPort = NULL;
|
serialPortUsage->serialPort = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable)
|
void serialInit(bool softserialEnabled)
|
||||||
{
|
{
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
|
|
||||||
|
@ -451,12 +451,6 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
||||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||||
serialPortUsageList[index].identifier = serialPortIdentifiers[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 (!softserialEnabled) {
|
||||||
if (0
|
if (0
|
||||||
#ifdef USE_SOFTSERIAL1
|
#ifdef USE_SOFTSERIAL1
|
||||||
|
|
|
@ -138,7 +138,7 @@ typedef void serialConsumer(uint8_t);
|
||||||
//
|
//
|
||||||
// configuration
|
// configuration
|
||||||
//
|
//
|
||||||
void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisable);
|
void serialInit(bool softserialEnabled);
|
||||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||||
uint8_t serialGetAvailablePortCount(void);
|
uint8_t serialGetAvailablePortCount(void);
|
||||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||||
|
|
|
@ -199,7 +199,7 @@ navigationPosControl_t posControl;
|
||||||
navSystemStatus_t NAV_Status;
|
navSystemStatus_t NAV_Status;
|
||||||
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
// Blackbox states
|
||||||
int16_t navCurrentState;
|
int16_t navCurrentState;
|
||||||
int16_t navActualVelocity[3];
|
int16_t navActualVelocity[3];
|
||||||
int16_t navDesiredVelocity[3];
|
int16_t navDesiredVelocity[3];
|
||||||
|
@ -212,7 +212,7 @@ uint16_t navFlags;
|
||||||
uint16_t navEPH;
|
uint16_t navEPH;
|
||||||
uint16_t navEPV;
|
uint16_t navEPV;
|
||||||
int16_t navAccNEU[3];
|
int16_t navAccNEU[3];
|
||||||
#endif
|
//End of blackbox states
|
||||||
|
|
||||||
static fpVector3_t * rthGetHomeTargetPosition(rthTargetMode_e mode);
|
static fpVector3_t * rthGetHomeTargetPosition(rthTargetMode_e mode);
|
||||||
static void updateDesiredRTHAltitude(void);
|
static void updateDesiredRTHAltitude(void);
|
||||||
|
@ -774,12 +774,13 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
||||||
[NAV_STATE_WAYPOINT_FINISHED] = {
|
[NAV_STATE_WAYPOINT_FINISHED] = {
|
||||||
.persistentId = NAV_PERSISTENT_ID_WAYPOINT_FINISHED,
|
.persistentId = NAV_PERSISTENT_ID_WAYPOINT_FINISHED,
|
||||||
.onEntry = navOnEnteringState_NAV_STATE_WAYPOINT_FINISHED,
|
.onEntry = navOnEnteringState_NAV_STATE_WAYPOINT_FINISHED,
|
||||||
.timeoutMs = 0,
|
.timeoutMs = 10,
|
||||||
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_WP | NAV_AUTO_WP_DONE,
|
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_WP | NAV_AUTO_WP_DONE,
|
||||||
.mapToFlightModes = NAV_WP_MODE | NAV_ALTHOLD_MODE,
|
.mapToFlightModes = NAV_WP_MODE | NAV_ALTHOLD_MODE,
|
||||||
.mwState = MW_NAV_STATE_WP_ENROUTE,
|
.mwState = MW_NAV_STATE_WP_ENROUTE,
|
||||||
.mwError = MW_NAV_ERROR_FINISH,
|
.mwError = MW_NAV_ERROR_FINISH,
|
||||||
.onEvent = {
|
.onEvent = {
|
||||||
|
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_WAYPOINT_FINISHED,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE,
|
[NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE,
|
||||||
|
@ -803,7 +804,9 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
||||||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS,
|
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS,
|
||||||
[NAV_FSM_EVENT_ERROR] = NAV_STATE_IDLE,
|
[NAV_FSM_EVENT_ERROR] = NAV_STATE_IDLE,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_IDLE, // ALTHOLD also bails out from emergency (to IDLE, AltHold will take over from there)
|
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||||
|
[NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE,
|
||||||
|
[NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE,
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|
||||||
|
@ -819,7 +822,9 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
||||||
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS, // re-process the state
|
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS, // re-process the state
|
||||||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_FINISHED,
|
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_FINISHED,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_IDLE, // ALTHOLD also bails out from emergency (to IDLE, AltHold will take over from there)
|
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||||
|
[NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE,
|
||||||
|
[NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE,
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
|
||||||
|
@ -1105,8 +1110,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
|
||||||
{
|
{
|
||||||
navigationFSMStateFlags_t prevFlags = navGetStateFlags(previousState);
|
navigationFSMStateFlags_t prevFlags = navGetStateFlags(previousState);
|
||||||
|
|
||||||
if ((posControl.flags.estHeadingStatus == EST_NONE) || (posControl.flags.estAltStatus == EST_NONE) || (posControl.flags.estPosStatus != EST_TRUSTED) || !STATE(GPS_FIX_HOME)) {
|
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
|
// Heading sensor, altitude sensor and HOME fix are mandatory for RTH. If not satisfied - switch to emergency landing
|
||||||
|
// Relevant to failsafe forced RTH only. Switched RTH blocked in selectNavEventFromBoxModeInput if sensors unavailanle.
|
||||||
// If we are in dead-reckoning mode - also fail, since coordinates may be unreliable
|
// If we are in dead-reckoning mode - also fail, since coordinates may be unreliable
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
}
|
}
|
||||||
|
@ -1162,8 +1168,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_INITIALIZE(navigati
|
||||||
return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_RTH_CLIMB_TO_SAFE_ALT
|
return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_RTH_CLIMB_TO_SAFE_ALT
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/* Position sensor failure timeout - land */
|
/* Position sensor failure timeout - land. Land immediately if failsafe RTH and timeout disabled (set to 0) */
|
||||||
else if (checkForPositionSensorTimeout()) {
|
else if (checkForPositionSensorTimeout() || (!navConfig()->general.pos_failure_timeout && posControl.flags.forcedRTHActivated)) {
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
}
|
}
|
||||||
/* No valid POS sensor but still within valid timeout - wait */
|
/* No valid POS sensor but still within valid timeout - wait */
|
||||||
|
@ -1330,7 +1336,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HOVER_ABOVE_HOME(na
|
||||||
{
|
{
|
||||||
UNUSED(previousState);
|
UNUSED(previousState);
|
||||||
|
|
||||||
if (!(validateRTHSanityChecker() || (posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()))
|
if (posControl.flags.estHeadingStatus == EST_NONE || !(validateRTHSanityChecker() || (posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()))
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
|
|
||||||
fpVector3_t * tmpHomePos = rthGetHomeTargetPosition(RTH_HOME_FINAL_HOVER);
|
fpVector3_t * tmpHomePos = rthGetHomeTargetPosition(RTH_HOME_FINAL_HOVER);
|
||||||
|
@ -1369,8 +1375,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF
|
||||||
return NAV_FSM_EVENT_SUCCESS;
|
return NAV_FSM_EVENT_SUCCESS;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (!validateRTHSanityChecker()) {
|
/* If position sensors unavailable - land immediately (wait for timeout on GPS)
|
||||||
// Continue to check for RTH sanity during landing
|
* Continue to check for RTH sanity during landing */
|
||||||
|
if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout() ||!validateRTHSanityChecker()) {
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1565,8 +1572,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na
|
||||||
UNREACHABLE();
|
UNREACHABLE();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/* No pos sensor available for NAV_WAIT_FOR_GPS_TIMEOUT_MS - land */
|
/* If position sensors unavailable - land immediately (wait for timeout on GPS) */
|
||||||
else if (checkForPositionSensorTimeout()) {
|
else if (checkForPositionSensorTimeout() || (posControl.flags.estHeadingStatus == EST_NONE)) {
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -1606,6 +1613,11 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_HOLD_TIME(navi
|
||||||
{
|
{
|
||||||
UNUSED(previousState);
|
UNUSED(previousState);
|
||||||
|
|
||||||
|
/* If position sensors unavailable - land immediately (wait for timeout on GPS) */
|
||||||
|
if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout()) {
|
||||||
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
|
}
|
||||||
|
|
||||||
timeMs_t currentTime = millis();
|
timeMs_t currentTime = millis();
|
||||||
|
|
||||||
if(posControl.waypointList[posControl.activeWaypointIndex].p1 <= 0)
|
if(posControl.waypointList[posControl.activeWaypointIndex].p1 <= 0)
|
||||||
|
@ -1950,12 +1962,11 @@ void updateActualHorizontalPositionAndVelocity(bool estPosValid, bool estVelVali
|
||||||
posControl.flags.horizontalPositionDataNew = 0;
|
posControl.flags.horizontalPositionDataNew = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
//Update blackbox data
|
||||||
navLatestActualPosition[X] = newX;
|
navLatestActualPosition[X] = newX;
|
||||||
navLatestActualPosition[Y] = newY;
|
navLatestActualPosition[Y] = newY;
|
||||||
navActualVelocity[X] = constrain(newVelX, -32678, 32767);
|
navActualVelocity[X] = constrain(newVelX, -32678, 32767);
|
||||||
navActualVelocity[Y] = constrain(newVelY, -32678, 32767);
|
navActualVelocity[Y] = constrain(newVelY, -32678, 32767);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
|
@ -2005,10 +2016,9 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo
|
||||||
posControl.actualState.surfaceMin = -1;
|
posControl.actualState.surfaceMin = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
//Update blackbox data
|
||||||
navLatestActualPosition[Z] = navGetCurrentActualPositionAndVelocity()->pos.z;
|
navLatestActualPosition[Z] = navGetCurrentActualPositionAndVelocity()->pos.z;
|
||||||
navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
|
navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
|
@ -3066,7 +3076,7 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
||||||
{
|
{
|
||||||
const timeUs_t currentTimeUs = micros();
|
const timeUs_t currentTimeUs = micros();
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
//Updata blackbox data
|
||||||
navFlags = 0;
|
navFlags = 0;
|
||||||
if (posControl.flags.estAltStatus == EST_TRUSTED) navFlags |= (1 << 0);
|
if (posControl.flags.estAltStatus == EST_TRUSTED) navFlags |= (1 << 0);
|
||||||
if (posControl.flags.estAglStatus == EST_TRUSTED) navFlags |= (1 << 1);
|
if (posControl.flags.estAglStatus == EST_TRUSTED) navFlags |= (1 << 1);
|
||||||
|
@ -3076,7 +3086,6 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
||||||
if (isGPSGlitchDetected()) navFlags |= (1 << 4);
|
if (isGPSGlitchDetected()) navFlags |= (1 << 4);
|
||||||
#endif
|
#endif
|
||||||
if (posControl.flags.estHeadingStatus == EST_TRUSTED) navFlags |= (1 << 5);
|
if (posControl.flags.estHeadingStatus == EST_TRUSTED) navFlags |= (1 << 5);
|
||||||
#endif
|
|
||||||
|
|
||||||
// Reset all navigation requests - NAV controllers will set them if necessary
|
// Reset all navigation requests - NAV controllers will set them if necessary
|
||||||
DISABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
|
DISABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
|
||||||
|
@ -3111,8 +3120,7 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
||||||
if (posControl.flags.verticalPositionDataConsumed)
|
if (posControl.flags.verticalPositionDataConsumed)
|
||||||
posControl.flags.verticalPositionDataNew = 0;
|
posControl.flags.verticalPositionDataNew = 0;
|
||||||
|
|
||||||
|
//Update blackbox data
|
||||||
#if defined(NAV_BLACKBOX)
|
|
||||||
if (posControl.flags.isAdjustingPosition) navFlags |= (1 << 6);
|
if (posControl.flags.isAdjustingPosition) navFlags |= (1 << 6);
|
||||||
if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7);
|
if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7);
|
||||||
if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8);
|
if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8);
|
||||||
|
@ -3120,7 +3128,6 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
||||||
navTargetPosition[X] = lrintf(posControl.desiredState.pos.x);
|
navTargetPosition[X] = lrintf(posControl.desiredState.pos.x);
|
||||||
navTargetPosition[Y] = lrintf(posControl.desiredState.pos.y);
|
navTargetPosition[Y] = lrintf(posControl.desiredState.pos.y);
|
||||||
navTargetPosition[Z] = lrintf(posControl.desiredState.pos.z);
|
navTargetPosition[Z] = lrintf(posControl.desiredState.pos.z);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
|
@ -3181,6 +3188,18 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
||||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Keep Emergency landing mode active once triggered. Is deactivated when landing in progress if WP or RTH cancelled
|
||||||
|
* or position sensors working again or if Manual or Althold modes selected.
|
||||||
|
* Remains active if landing finished regardless of sensor status or if WP or RTH modes still selected */
|
||||||
|
if (navigationIsExecutingAnEmergencyLanding()) {
|
||||||
|
if (!(canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME)) &&
|
||||||
|
!IS_RC_MODE_ACTIVE(BOXMANUAL) &&
|
||||||
|
!(IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) && canActivateAltHold) &&
|
||||||
|
(IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVRTH))) {
|
||||||
|
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Keep canActivateWaypoint flag at FALSE if there is no mission loaded
|
// Keep canActivateWaypoint flag at FALSE if there is no mission loaded
|
||||||
// Also block WP mission if we are executing RTH
|
// Also block WP mission if we are executing RTH
|
||||||
if (!isWaypointMissionValid() || isExecutingRTH) {
|
if (!isWaypointMissionValid() || isExecutingRTH) {
|
||||||
|
@ -3469,9 +3488,8 @@ void updateWaypointsAndNavigationMode(void)
|
||||||
// Map navMode back to enabled flight modes
|
// Map navMode back to enabled flight modes
|
||||||
switchNavigationFlightModes();
|
switchNavigationFlightModes();
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
//Update Blackbox data
|
||||||
navCurrentState = (int16_t)posControl.navPersistentId;
|
navCurrentState = (int16_t)posControl.navPersistentId;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/*-----------------------------------------------------------
|
||||||
|
|
|
@ -69,9 +69,6 @@ bool findNearestSafeHome(void); // Find nearest safehome
|
||||||
#endif // defined(USE_SAFE_HOME)
|
#endif // defined(USE_SAFE_HOME)
|
||||||
|
|
||||||
#if defined(USE_NAV)
|
#if defined(USE_NAV)
|
||||||
#if defined(USE_BLACKBOX)
|
|
||||||
#define NAV_BLACKBOX
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef NAV_MAX_WAYPOINTS
|
#ifndef NAV_MAX_WAYPOINTS
|
||||||
#define NAV_MAX_WAYPOINTS 15
|
#define NAV_MAX_WAYPOINTS 15
|
||||||
|
|
|
@ -98,9 +98,7 @@ static void updateAltitudeVelocityController_MC(timeDelta_t deltaMicros)
|
||||||
posControl.desiredState.vel.z = targetVel;
|
posControl.desiredState.vel.z = targetVel;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
|
||||||
navDesiredVelocity[Z] = constrain(lrintf(posControl.desiredState.vel.z), -32678, 32767);
|
navDesiredVelocity[Z] = constrain(lrintf(posControl.desiredState.vel.z), -32678, 32767);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros)
|
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.x = newVelX * velHeadFactor * velExpoFactor;
|
||||||
posControl.desiredState.vel.y = newVelY * velHeadFactor * velExpoFactor;
|
posControl.desiredState.vel.y = newVelY * velHeadFactor * velExpoFactor;
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
|
||||||
navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
|
navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
|
||||||
navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
|
navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static float computeNormalizedVelocity(const float value, const float maxValue)
|
static float computeNormalizedVelocity(const float value, const float maxValue)
|
||||||
|
|
|
@ -443,12 +443,10 @@ static void updateIMUTopic(timeUs_t currentTimeUs)
|
||||||
posEstimator.imu.accelNEU.z = 0;
|
posEstimator.imu.accelNEU.z = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
|
||||||
/* Update blackbox values */
|
/* Update blackbox values */
|
||||||
navAccNEU[X] = posEstimator.imu.accelNEU.x;
|
navAccNEU[X] = posEstimator.imu.accelNEU.x;
|
||||||
navAccNEU[Y] = posEstimator.imu.accelNEU.y;
|
navAccNEU[Y] = posEstimator.imu.accelNEU.y;
|
||||||
navAccNEU[Z] = posEstimator.imu.accelNEU.z;
|
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);
|
updateActualAltitudeAndClimbRate(false, posEstimator.est.pos.z, 0, posEstimator.est.aglAlt, 0, EST_NONE);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(NAV_BLACKBOX)
|
//Update Blackbox states
|
||||||
navEPH = posEstimator.est.eph;
|
navEPH = posEstimator.est.eph;
|
||||||
navEPV = posEstimator.est.epv;
|
navEPV = posEstimator.est.epv;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -58,8 +58,8 @@ static timeUs_t crsfFrameStartAt = 0;
|
||||||
static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
|
static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
|
||||||
static uint8_t telemetryBufLen = 0;
|
static uint8_t telemetryBufLen = 0;
|
||||||
|
|
||||||
// The power levels represented by uplinkTXPower above in mW (250mW added to full TX in v4.00 firmware)
|
// 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};
|
const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000, 250, 50};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* CRSF protocol
|
* CRSF protocol
|
||||||
|
|
|
@ -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
|
|
||||||
|
|
|
@ -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);
|
|
|
@ -37,7 +37,6 @@
|
||||||
|
|
||||||
|
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/rx_pwm.h"
|
|
||||||
#include "drivers/rx_spi.h"
|
#include "drivers/rx_spi.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
@ -60,7 +59,6 @@
|
||||||
#include "rx/fport2.h"
|
#include "rx/fport2.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
#include "rx/msp_override.h"
|
#include "rx/msp_override.h"
|
||||||
#include "rx/pwm.h"
|
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
#include "rx/sbus.h"
|
#include "rx/sbus.h"
|
||||||
#include "rx/spektrum.h"
|
#include "rx/spektrum.h"
|
||||||
|
@ -110,7 +108,7 @@ rxLinkStatistics_t rxLinkStatistics;
|
||||||
rxRuntimeConfig_t rxRuntimeConfig;
|
rxRuntimeConfig_t rxRuntimeConfig;
|
||||||
static uint8_t rcSampleIndex = 0;
|
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
|
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||||
|
@ -285,7 +283,6 @@ void rxInit(void)
|
||||||
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
||||||
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
|
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
|
||||||
rxRuntimeConfig.rxSignalTimeout = DELAY_10_HZ;
|
rxRuntimeConfig.rxSignalTimeout = DELAY_10_HZ;
|
||||||
rxRuntimeConfig.requireFiltering = false;
|
|
||||||
rcSampleIndex = 0;
|
rcSampleIndex = 0;
|
||||||
|
|
||||||
timeMs_t nowMs = millis();
|
timeMs_t nowMs = millis();
|
||||||
|
@ -317,15 +314,6 @@ void rxInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (rxConfig()->receiverType) {
|
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
|
#ifdef USE_SERIAL_RX
|
||||||
case RX_TYPE_SERIAL:
|
case RX_TYPE_SERIAL:
|
||||||
|
@ -477,39 +465,6 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
|
||||||
return result;
|
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)
|
bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
int16_t rcStaging[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
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
|
// 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 receiver is in failsafe (not receiving signal or sending invalid channel values) - last good input values are retained
|
||||||
if (rxFlightChannelsValid && rxSignalReceived) {
|
if (rxFlightChannelsValid && rxSignalReceived) {
|
||||||
if (rxRuntimeConfig.requireFiltering) {
|
for (int channel = 0; channel < rxChannelCount; channel++) {
|
||||||
for (int channel = 0; channel < rxChannelCount; channel++) {
|
rcChannels[channel].data = rcStaging[channel];
|
||||||
rcChannels[channel].data = applyChannelFiltering(channel, rcStaging[channel]);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
for (int channel = 0; channel < rxChannelCount; channel++) {
|
|
||||||
rcChannels[channel].data = rcStaging[channel];
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -51,6 +51,8 @@
|
||||||
|
|
||||||
#define RSSI_MAX_VALUE 1023
|
#define RSSI_MAX_VALUE 1023
|
||||||
|
|
||||||
|
#define PPM_RCVR_TIMEOUT 0
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
RX_FRAME_PENDING = 0, // No new data available from receiver
|
RX_FRAME_PENDING = 0, // No new data available from receiver
|
||||||
RX_FRAME_COMPLETE = (1 << 0), // There is new data available
|
RX_FRAME_COMPLETE = (1 << 0), // There is new data available
|
||||||
|
@ -61,11 +63,9 @@ typedef enum {
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
RX_TYPE_NONE = 0,
|
RX_TYPE_NONE = 0,
|
||||||
RX_TYPE_PPM = 1,
|
RX_TYPE_SERIAL = 1,
|
||||||
RX_TYPE_SERIAL = 2,
|
RX_TYPE_MSP = 2,
|
||||||
RX_TYPE_MSP = 3,
|
RX_TYPE_SPI = 3
|
||||||
RX_TYPE_SPI = 4,
|
|
||||||
RX_TYPE_UNUSED_1 = 5
|
|
||||||
} rxReceiverType_e;
|
} rxReceiverType_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -162,7 +162,6 @@ typedef struct rxRuntimeConfig_s {
|
||||||
uint8_t channelCount; // number of rc channels as reported by current input driver
|
uint8_t channelCount; // number of rc channels as reported by current input driver
|
||||||
timeUs_t rxRefreshRate;
|
timeUs_t rxRefreshRate;
|
||||||
timeUs_t rxSignalTimeout;
|
timeUs_t rxSignalTimeout;
|
||||||
bool requireFiltering;
|
|
||||||
rcReadRawDataFnPtr rcReadRawFn;
|
rcReadRawDataFnPtr rcReadRawFn;
|
||||||
rcFrameStatusFnPtr rcFrameStatusFn;
|
rcFrameStatusFnPtr rcFrameStatusFn;
|
||||||
rcProcessFrameFnPtr rcProcessFrameFn;
|
rcProcessFrameFnPtr rcProcessFrameFn;
|
||||||
|
|
|
@ -126,7 +126,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
#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 DISABLE_RX_PWM_FEATURE
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)
|
||||||
|
|
||||||
|
|
|
@ -74,7 +74,6 @@
|
||||||
#define USE_UART2 // Receiver - RX (PA3)
|
#define USE_UART2 // Receiver - RX (PA3)
|
||||||
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
#define AVOID_UART2_FOR_PWM_PPM
|
|
||||||
|
|
||||||
#define UART1_TX_PIN PB6
|
#define UART1_TX_PIN PB6
|
||||||
#define UART1_RX_PIN PB7
|
#define UART1_RX_PIN PB7
|
||||||
|
|
|
@ -116,7 +116,7 @@
|
||||||
|
|
||||||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
#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
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
|
|
@ -142,10 +142,6 @@
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
// Disable PWM & PPM inputs
|
|
||||||
#undef USE_RX_PWM
|
|
||||||
#undef USE_RX_PPM
|
|
||||||
|
|
||||||
// Set default UARTs
|
// Set default UARTs
|
||||||
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
|
|
|
@ -147,10 +147,6 @@
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
// Disable PWM & PPM inputs
|
|
||||||
#undef USE_RX_PWM
|
|
||||||
#undef USE_RX_PPM
|
|
||||||
|
|
||||||
// Set default UARTs
|
// Set default UARTs
|
||||||
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
|
|
|
@ -131,7 +131,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#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 DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
|
@ -134,7 +134,7 @@
|
||||||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_BLACKBOX)
|
#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
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
|
|
|
@ -56,7 +56,6 @@
|
||||||
#define USE_UART4
|
#define USE_UART4
|
||||||
#define USE_UART5
|
#define USE_UART5
|
||||||
#define SERIAL_PORT_COUNT 5
|
#define SERIAL_PORT_COUNT 5
|
||||||
#define AVOID_UART2_FOR_PWM_PPM
|
|
||||||
|
|
||||||
#define UART1_TX_PIN PC4
|
#define UART1_TX_PIN PC4
|
||||||
#define UART1_RX_PIN PC5
|
#define UART1_RX_PIN PC5
|
||||||
|
|
|
@ -29,9 +29,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS,
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const timerHardware_t timerHardware[] = {
|
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)
|
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(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, 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)
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(2, 4, 7)
|
||||||
|
|
|
@ -91,9 +91,6 @@
|
||||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
||||||
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
||||||
|
|
||||||
#undef USE_RX_PWM
|
|
||||||
#undef USE_RX_PPM
|
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_TELEMETRY)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_TELEMETRY)
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
|
@ -130,7 +130,7 @@
|
||||||
#define USE_RANGEFINDER
|
#define USE_RANGEFINDER
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
#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
|
#define USE_SPEKTRUM_BIND
|
||||||
// UART3,
|
// UART3,
|
||||||
|
|
|
@ -76,8 +76,6 @@
|
||||||
|
|
||||||
#define MAX_PWM_OUTPUT_PORTS 12
|
#define MAX_PWM_OUTPUT_PORTS 12
|
||||||
|
|
||||||
#define AVOID_UART2_FOR_PWM_PPM
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -134,7 +134,7 @@
|
||||||
|
|
||||||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
#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 RX_CHANNELS_TAER
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD)
|
||||||
|
|
||||||
|
|
|
@ -94,7 +94,7 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#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)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
|
||||||
|
|
||||||
// Number of available PWM outputs
|
// Number of available PWM outputs
|
||||||
|
|
|
@ -26,8 +26,9 @@
|
||||||
#include "drivers/pinio.h"
|
#include "drivers/pinio.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
BUSDEV_REGISTER_SPI_TAG(busdev_imu1_6000, DEVHW_MPU6000, IMU1_SPI_BUS, IMU1_CS_PIN, IMU1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU1_ALIGN);
|
BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||||
BUSDEV_REGISTER_SPI_TAG(busdev_imu2_6500, DEVHW_MPU6500, IMU2_SPI_BUS, IMU2_CS_PIN, IMU2_EXTI_PIN, 1, DEVFLAGS_NONE, IMU2_ALIGN);
|
BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||||
|
BUSDEV_REGISTER_SPI_TAG(busdev_imu2, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 2, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||||
|
|
||||||
const timerHardware_t timerHardware[] = {
|
const timerHardware_t timerHardware[] = {
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
// *************** SPI1 IMU1 *************************
|
// *************** SPI1 IMU0 MPU6000 ****************
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define SPI1_SCK_PIN PA5
|
#define SPI1_SCK_PIN PA5
|
||||||
|
@ -46,12 +46,12 @@
|
||||||
|
|
||||||
#define USE_IMU_MPU6000
|
#define USE_IMU_MPU6000
|
||||||
|
|
||||||
#define IMU1_ALIGN CW0_DEG_FLIP
|
#define IMU_MPU6000_ALIGN CW0_DEG_FLIP
|
||||||
#define IMU1_SPI_BUS BUS_SPI1
|
#define MPU6000_SPI_BUS BUS_SPI1
|
||||||
#define IMU1_CS_PIN PC15
|
#define MPU6000_CS_PIN PC15
|
||||||
#define IMU1_EXTI_PIN PB2
|
#define MPU6000_EXTI_PIN PB2
|
||||||
|
|
||||||
// *************** SPI4 IMU2 *************************
|
// *************** SPI4 IMU1 ICM20602 **************
|
||||||
#define USE_SPI_DEVICE_4
|
#define USE_SPI_DEVICE_4
|
||||||
#define SPI4_SCK_PIN PE12
|
#define SPI4_SCK_PIN PE12
|
||||||
#define SPI4_MISO_PIN PE13
|
#define SPI4_MISO_PIN PE13
|
||||||
|
@ -59,10 +59,19 @@
|
||||||
|
|
||||||
#define USE_IMU_MPU6500
|
#define USE_IMU_MPU6500
|
||||||
|
|
||||||
#define IMU2_ALIGN CW0_DEG_FLIP
|
#define IMU_MPU6500_ALIGN CW0_DEG_FLIP
|
||||||
#define IMU2_SPI_BUS BUS_SPI4
|
#define MPU6500_SPI_BUS BUS_SPI4
|
||||||
#define IMU2_CS_PIN PE11
|
#define MPU6500_CS_PIN PE11
|
||||||
#define IMU2_EXTI_PIN PE15
|
#define MPU6500_EXTI_PIN PE15
|
||||||
|
|
||||||
|
// *************** SPI4 IMU2 ICM42605 **************
|
||||||
|
#define USE_IMU_ICM42605
|
||||||
|
|
||||||
|
#define IMU_ICM42605_ALIGN CW90_DEG_FLIP
|
||||||
|
#define ICM42605_SPI_BUS BUS_SPI4
|
||||||
|
#define ICM42605_CS_PIN PC13
|
||||||
|
#define ICM42605_EXTI_PIN PC14
|
||||||
|
|
||||||
|
|
||||||
// *************** SPI2 OSD ***********************
|
// *************** SPI2 OSD ***********************
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
|
@ -123,7 +123,7 @@
|
||||||
|
|
||||||
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
//#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 DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_OSD)
|
||||||
|
|
||||||
#define BUTTONS
|
#define BUTTONS
|
||||||
|
|
|
@ -258,7 +258,7 @@
|
||||||
#define WS2811_PIN PA1
|
#define WS2811_PIN PA1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
#define DISABLE_RX_PWM_FEATURE
|
#define DISABLE_RX_PWM_FEATURE
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)
|
||||||
|
|
||||||
|
|
|
@ -73,7 +73,6 @@
|
||||||
#define UART1_RX_PIN PA10
|
#define UART1_RX_PIN PA10
|
||||||
#define UART1_TX_PIN PA9
|
#define UART1_TX_PIN PA9
|
||||||
|
|
||||||
//#define AVOID_UART2_FOR_PWM_PPM
|
|
||||||
#define USE_UART2
|
#define USE_UART2
|
||||||
#define UART2_TX_PIN PA2 //not wired
|
#define UART2_TX_PIN PA2 //not wired
|
||||||
#define UART2_RX_PIN PA3
|
#define UART2_RX_PIN PA3
|
||||||
|
|
|
@ -154,7 +154,7 @@
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART6
|
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
|
@ -55,7 +55,6 @@
|
||||||
#define USE_UART2 // Input - RX (PA3)
|
#define USE_UART2 // Input - RX (PA3)
|
||||||
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
|
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
#define AVOID_UART2_FOR_PWM_PPM
|
|
||||||
|
|
||||||
#define UART1_TX_PIN PB6
|
#define UART1_TX_PIN PB6
|
||||||
#define UART1_RX_PIN PB7
|
#define UART1_RX_PIN PB7
|
||||||
|
@ -94,7 +93,7 @@
|
||||||
// #define USE_RANGEFINDER
|
// #define USE_RANGEFINDER
|
||||||
|
|
||||||
|
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
|
|
||||||
// Number of available PWM outputs
|
// Number of available PWM outputs
|
||||||
#define MAX_PWM_OUTPUT_PORTS 10
|
#define MAX_PWM_OUTPUT_PORTS 10
|
||||||
|
|
|
@ -101,7 +101,7 @@
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT)
|
||||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||||
|
|
||||||
#define USE_SPEKTRUM_BIND
|
#define USE_SPEKTRUM_BIND
|
||||||
#define BIND_PIN PB11 // UART3
|
#define BIND_PIN PB11 // UART3
|
||||||
|
|
|
@ -127,7 +127,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#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_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY)
|
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY)
|
||||||
|
|
||||||
#define USE_SPEKTRUM_BIND
|
#define USE_SPEKTRUM_BIND
|
||||||
|
|
|
@ -128,7 +128,7 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#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 DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||||
|
|
||||||
#define BUTTONS
|
#define BUTTONS
|
||||||
|
|
|
@ -39,7 +39,6 @@
|
||||||
#define I2C2_OVERCLOCK false
|
#define I2C2_OVERCLOCK false
|
||||||
#define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week
|
#define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week
|
||||||
|
|
||||||
#define USE_RX_PPM
|
|
||||||
#define USE_SERIAL_RX
|
#define USE_SERIAL_RX
|
||||||
#define USE_SERIALRX_SPEKTRUM // Cheap and fairly common protocol
|
#define USE_SERIALRX_SPEKTRUM // Cheap and fairly common protocol
|
||||||
#define USE_SERIALRX_SBUS // Very common protocol
|
#define USE_SERIALRX_SBUS // Very common protocol
|
||||||
|
|
|
@ -144,7 +144,8 @@ const exBusSensor_t jetiExSensors[] = {
|
||||||
{"G-Force X", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
{"G-Force X", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
||||||
{"G-Force Y", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
{"G-Force Y", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
||||||
{"G-Force Z", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
{"G-Force Z", "", EX_TYPE_22b, DECIMAL_MASK(3)},
|
||||||
{"RPM", "", EX_TYPE_22b, DECIMAL_MASK(0)}
|
{"RPM", "", EX_TYPE_22b, DECIMAL_MASK(0)},
|
||||||
|
{"Trip Distance", "m", EX_TYPE_22b, DECIMAL_MASK(0)}
|
||||||
};
|
};
|
||||||
|
|
||||||
// after every 15 sensors increment the step by 2 (e.g. ...EX_VAL15, EX_VAL16 = 17) to skip the device description
|
// after every 15 sensors increment the step by 2 (e.g. ...EX_VAL15, EX_VAL16 = 17) to skip the device description
|
||||||
|
@ -170,6 +171,7 @@ enum exSensors_e {
|
||||||
EX_GFORCE_Y,
|
EX_GFORCE_Y,
|
||||||
EX_GFORCE_Z,
|
EX_GFORCE_Z,
|
||||||
EX_RPM,
|
EX_RPM,
|
||||||
|
EX_TRIP_DISTANCE,
|
||||||
};
|
};
|
||||||
|
|
||||||
union{
|
union{
|
||||||
|
@ -211,6 +213,7 @@ void enableGpsTelemetry(bool enable)
|
||||||
bitArraySet(&exSensorEnabled, EX_GPS_DIRECTION_TO_HOME);
|
bitArraySet(&exSensorEnabled, EX_GPS_DIRECTION_TO_HOME);
|
||||||
bitArraySet(&exSensorEnabled, EX_GPS_HEADING);
|
bitArraySet(&exSensorEnabled, EX_GPS_HEADING);
|
||||||
bitArraySet(&exSensorEnabled, EX_GPS_ALTITUDE);
|
bitArraySet(&exSensorEnabled, EX_GPS_ALTITUDE);
|
||||||
|
bitArraySet(&exSensorEnabled, EX_TRIP_DISTANCE);
|
||||||
} else {
|
} else {
|
||||||
bitArrayClr(&exSensorEnabled, EX_GPS_SATS);
|
bitArrayClr(&exSensorEnabled, EX_GPS_SATS);
|
||||||
bitArrayClr(&exSensorEnabled, EX_GPS_LONG);
|
bitArrayClr(&exSensorEnabled, EX_GPS_LONG);
|
||||||
|
@ -220,6 +223,7 @@ void enableGpsTelemetry(bool enable)
|
||||||
bitArrayClr(&exSensorEnabled, EX_GPS_DIRECTION_TO_HOME);
|
bitArrayClr(&exSensorEnabled, EX_GPS_DIRECTION_TO_HOME);
|
||||||
bitArrayClr(&exSensorEnabled, EX_GPS_HEADING);
|
bitArrayClr(&exSensorEnabled, EX_GPS_HEADING);
|
||||||
bitArrayClr(&exSensorEnabled, EX_GPS_ALTITUDE);
|
bitArrayClr(&exSensorEnabled, EX_GPS_ALTITUDE);
|
||||||
|
bitArrayClr(&exSensorEnabled, EX_TRIP_DISTANCE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -419,6 +423,9 @@ int32_t getSensorValue(uint8_t sensor)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case EX_TRIP_DISTANCE:
|
||||||
|
return getTotalTravelDistance() / 100;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue