diff --git a/.travis.sh b/.travis.sh
index 7332d8aaaf..7e5d780831 100755
--- a/.travis.sh
+++ b/.travis.sh
@@ -66,16 +66,21 @@ elif [ $TARGET ] ; then
fi
elif [ $GOAL ] ; then
+ if [ "test" == "$GOAL" ] ; then
+ $MAKE check-target-independence || exit $?
+ $MAKE check-fastram-usage-correctness || exit $?
+ fi
+
$MAKE $GOAL || exit $?
- if [ $PUBLISHCOV ] ; then
- if [ "test" == "$GOAL" ] ; then
- lcov --directory . -b src/test --capture --output-file coverage.info 2>&1 | grep -E ":version '402\*', prefer.*'406\*" --invert-match
- lcov --remove coverage.info 'lib/test/*' 'src/test/*' '/usr/*' --output-file coverage.info # filter out system and test code
- lcov --list coverage.info # debug before upload
- coveralls-lcov coverage.info # uploads to coveralls
+ if [ $PUBLISHCOV ] ; then
+ if [ "test" == "$GOAL" ] ; then
+ lcov --directory . -b src/test --capture --output-file coverage.info 2>&1 | grep -E ":version '402\*', prefer.*'406\*" --invert-match
+ lcov --remove coverage.info 'lib/test/*' 'src/test/*' '/usr/*' --output-file coverage.info # filter out system and test code
+ lcov --list coverage.info # debug before upload
+ coveralls-lcov coverage.info # uploads to coveralls
+ fi
fi
- fi
else
$MAKE all
fi
diff --git a/.travis.yml b/.travis.yml
index 2439f09a03..2c6eb9e53a 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -1,3 +1,26 @@
+os:
+ - linux
+
+sudo: false
+
+dist: trusty
+
+addons:
+ apt:
+ packages:
+ - lcov
+ - build-essential
+ - git
+ - libc6-i386
+ - time
+ - libblocksruntime-dev
+
+git:
+ depth: 5
+
+# We use cpp for unit tests, and c for the main project.
+language: cpp
+compiler: clang
env:
# - PUBLISHMETA=True
@@ -18,28 +41,6 @@ env:
# - TARGET=AIORACERF3
# - TARGET=...
-# use new docker environment
-sudo: false
-
-git:
- depth: 5
-
-addons:
- apt:
- packages:
- - lcov
- - build-essential
- - git
- - libc6-i386
- - time
- - libblocksruntime-dev
-
-# We use cpp for unit tests, and c for the main project.
-language: cpp
-compiler: clang
-dist: trusty
-
-
before_install:
- pip install --user cpp-coveralls
- gem install coveralls-lcov
@@ -48,7 +49,7 @@ install:
- make arm_sdk_install
before_script:
- - tools/gcc-arm-none-eabi-7-2017-q4-major/bin/arm-none-eabi-gcc --version
+ - make arm_sdk_version
- clang --version
- clang++ --version
- gcc --version
@@ -60,12 +61,6 @@ cache:
- downloads
- tools
-
-#notifications:
-# irc: "chat.freenode.net#cleanflight"
-# use_notice: true
-# skip_join: true
-
notifications:
slack: betaflightgroup:LQSj02nsBEdefcO5UQcLgB0U
webhooks:
diff --git a/Makefile b/Makefile
index 89b72b53c0..80595b78dc 100644
--- a/Makefile
+++ b/Makefile
@@ -477,7 +477,7 @@ test junittest:
check-target-independence:
$(V1) for test_target in $(VALID_TARGETS); do \
- FOUND=$$(grep -rP "\W$${test_target}\W?" src/main/ | grep -vP "(\/\/)|(\/\*).*\W$${test_target}\W?" | grep -vP "^src/main/target"); \
+ FOUND=$$(grep -rE "\W$${test_target}\W?" src/main | grep -vE "(//)|(/\*).*\W$${test_target}\W?" | grep -vE "^src/main/target"); \
if [ "$${FOUND}" != "" ]; then \
echo "Target dependencies found:"; \
echo "$${FOUND}"; \
@@ -485,6 +485,21 @@ check-target-independence:
fi; \
done
+check-fastram-usage-correctness:
+ $(V1) NON_TRIVIALLY_INITIALIZED=$$(grep -Ern "\W?FAST_RAM_ZERO_INIT\W.*=.*" src/main/ | grep -Ev "=\s*(false|NULL|0(\.0*f?)?)\s*[,;]"); \
+ if [ "$${NON_TRIVIALLY_INITIALIZED}" != "" ]; then \
+ echo "Non-trivially initialized FAST_RAM_ZERO_INIT variables found, use FAST_RAM instead:"; \
+ echo "$${NON_TRIVIALLY_INITIALIZED}"; \
+ exit 1; \
+ fi; \
+ TRIVIALLY_INITIALIZED=$$(grep -Ern "\W?FAST_RAM\W.*;" src/main/ | grep -v "="); \
+ EXPLICITLY_TRIVIALLY_INITIALIZED=$$(grep -Ern "\W?FAST_RAM\W.*;" src/main/ | grep -E "=\s*(false|NULL|0(\.0*f?)?)\s*[,;]"); \
+ if [ "$${TRIVIALLY_INITIALIZED}$${EXPLICITLY_TRIVIALLY_INITIALIZED}" != "" ]; then \
+ echo "Trivially initialized FAST_RAM variables found, use FAST_RAM_ZERO_INIT instead to save FLASH:"; \
+ echo "$${TRIVIALLY_INITIALIZED}\n$${EXPLICITLY_TRIVIALLY_INITIALIZED}"; \
+ exit 1; \
+ fi;
+
# rebuild everything when makefile changes
$(TARGET_OBJS) : Makefile
diff --git a/docs/boards/Board - FOXEERF405.md b/docs/boards/Board - FOXEERF405.md
new file mode 100644
index 0000000000..dc83520bf2
--- /dev/null
+++ b/docs/boards/Board - FOXEERF405.md
@@ -0,0 +1,21 @@
+# Board - FOXEERF405
+
+The FOXEERF405 described here:
+
+This board use the STM32F405RGT6 microcontroller and have the following features:
+* 1024K bytes of flash memory,192K bytes RAM,168 MHz CPU/210 DMIPS
+* The 16M byte SPI flash for data logging
+* USB VCP and boot select button on board(for DFU)
+* Stable voltage regulation,9V/2A DCDC BEC for VTX/camera etc.And could select 5v/9v with pad
+* Serial LED interface(LED_STRIP)
+* VBAT/CURR/RSSI sensors input
+* Suppose IRC Tramp/smart audio/FPV Camera Control/FPORT/telemetry
+* Supports SBus, Spektrum1024/2048, PPM. No external inverters required (built-in).
+* Supports I2C device extend(baro/compass/OLED etc)
+* Supports GPS
+* Supports MPU6000 or ICM20689
+
+
+
+
+
diff --git a/docs/boards/Board - Matek F405-CTR.md b/docs/boards/Board - Matek F405-CTR.md
index a8afd35947..3a8d85f4a4 100644
--- a/docs/boards/Board - Matek F405-CTR.md
+++ b/docs/boards/Board - Matek F405-CTR.md
@@ -6,34 +6,36 @@ Full details on the Matek Sys F405-CTR can be found on the Matek Website: [matek
* *Mass:* ~10g
* *PCB Size:* 36x46mm
+ * 30x30mm Hole pattern (M4 size, M3 size with rubber isolators)
### FC Specs
* Processors and Sensors
- * *MCU:* 168MHz STM32F405
- * *IMU:* MPU6000 accelerometer/gyro (via SPI)
- * *Baro:* BMP280 (via I2C)
- * *OSD:* BetaFlight OSD w/ AT7456E chip
+ * *MCU:* [STM32F405RGT6](http://www.st.com/content/ccc/resource/technical/document/datasheet/ef/92/76/6d/bb/c2/4f/f7/DM00037051.pdf/files/DM00037051.pdf/jcr:content/translations/en.DM00037051.pdf)
+ * *IMU:* [MPU6000](https://www.invensense.com/wp-content/uploads/2015/02/MPU-6000-Datasheet1.pdf) (connected via SPI)
+ * *Baro:* [BMP280](https://ae-bst.resource.bosch.com/media/_tech/media/datasheets/BST-BMP280-DS001-19.pdf) (connected via I2C)
+ * *OSD:* BetaFlight OSD (AT7456E IC)
* *Blackbox:* MicroSD card slot (SD/SDHC)
* 5 UARTs
- * Smartaudio & Tramp VTX protocol supported
### Integrated PDB Specs
* *Input:* 6-30v (3-6S LiPo) w/TVS protection
-* *PDB:* Rated 4x30A per ESC pad set (Max. 4x46A burst)
-* *BEC:* 5v 2A continuous load (Max. 3A burst)
-* *LDO:* 3.3v: Max load: 300mA for Spektrum RX
-* *Current Sensor:* Rated for 184A (*Suggested scale value `179`*)
-* *Voltage Sensor:* 1:10 (*Suggested scale value `110`*)
+* *ESC Pads:* Rated 4x30A per ESC pad set (4x46A burst)
+* Voltage Regulators:
+ * *5v BEC:* 2A continuous load (3A burst)
+ * *3.3v LDO:* max load: 300mA
+* Power Sense:
+ * *Current Sensor:* Rated for 184A (*Suggested scale value `179`*)
+ * *Voltage Sensor:* 1:10 signal output ratio (*Suggested scale value `110`*)
## Status LEDs
-| LED | Color | Color Codes |
-|------------:|-------|:--------------------------------------|
-| FC Status | Blue | *Unknown* |
-| FC Status | Red | *Unknown* |
-| 3v3 Status | Red | Red: active, Not lit: inactive |
+| LED | Color | Color Codes |
+|---------------:|-------|:----------------------------------------------------------------------------------------------------------|
+| FC Status | Blue | **Unlit:** USB disconnected and disarmed,
**Lit:** USB disconnected and armed,
**Flashing:** USB connected and disarmed,
**5x Rapid Flash then Flashing:** USB connected and arming command prevented |
+| Accelerometer | Red | Accelerometer status (Lit: active, Unlit: inactive) |
+| 3v3 Status | Red | Red: active, Unlit: inactive |
## Pinout
@@ -64,28 +66,28 @@ Pads are organised into two large banks of pads on left and right sides of board
| Pad Silkscreen Label | Function | Notes |
|---------------------:|---------------|:-----------------------------------------------------------------------------------------------|
-| `+ / -` | Battery In | 6-30vDC LiPo Power input (Battery +/- and 4-in-1 ESC +/- pads) |
-| `S1-S6` | ESC Out | (1-4 near ESC power connections, 5-6 on front) Supports PWM, Oneshot, Multishot, DSHOT |
-| `5V, GND, S1-S4` | ESC Out | (Rear of board) 4-in-1 ESC Out |
-| `VBT, GND` | VBT Out | Marked for VTX OSD, but could be used for whatever |
-| `CURR` | Current Sense | Current Sensor I/O pin (output from onboard sensor or input from external sensor) |
-| `5V` | | Out from internal 5v BEC (rated 2A continuous, 3A burst) |
-| `3V3` | | Out from 3v3 regulator (rated 300mA) |
-| `4V5` | | Out from 4v4~4v8 regulator (unknown rating, power is also supplied when connected via USB) |
+| `+ / -` | Battery In | 6-30vDC LiPo Power input (*Battery +/- and 4-in-1 ESC +/- pads*) |
+| `S1-S6` | ESC Out | (*1-4 near ESC power connections, 5-6 on front*) Supports PWM, Oneshot, Multishot, DSHOT |
+| `5V, GND, S1-S4` | ESC Out | (*Rear of board*) 4-in-1 ESC Out |
+| `VBT, GND` | VBT Out | VBAT power pad (*marked for VTX, but could be used for whatever*) |
+| `CURR` | Current Sense | Current Sensor I/O pin (*output from onboard sensor or input from external sensor*) |
+| `5V` | | Out from internal 5v BEC (*rated 2A continuous, 3A burst*) |
+| `3V3` | | Out from 3v3 regulator (*rated 300mA*) |
+| `4V5` | | Out from 4v4~4v8 regulator (*unknown rating, power is also supplied when connected via USB*) |
| `G` | GND | |
| `LED` | WS2812 Signal | |
| `Bz-, 5V` | Buzzer | |
| `Rssi` | RSSI | FrSky RSSI input from RX |
-| `G, 3V3, SDA, SLC` | I2C | (Rear of board) I2C connection marked for a magnetometer but could be used for whatever |
-| `VTX, Cam, DAC` | VTX/CAM | VTX: Video out, Cam: Video in, DAC: Cam control pin (since BF3.3, may be resourced to `S6` ) |
+| `G, 3V3, SDA, SLC` | I2C | (*Rear of board*) I2C connection marked for a magnetometer but could be used for whatever |
+| `VTX, Cam, DAC` | VTX/CAM | VTX: Video out, Cam: Video in, DAC: Cam control pin (*since BF3.3, may be resourced to `S6`*) |
| `RX1, TX1` | UART1 | |
| `TX2` | UART2-TX | May be reassigned to `softserial1` for use as FrSky SmartPort pad |
-| `RX2` | UART2-RX | RX connection for Spektrum DSMX or DSM2, FlySky iBUS, or PPM (Disable `UART2` for PPM) |
-| `Sbus` | SBUS (UART2) | Dedicated pad for SBUS (duplicate pad of `RX2` with signal inverter) |
+| `RX2` | UART2-RX | RX connection for Spektrum DSMX or DSM2, FlySky iBUS, or PPM (*Disable `UART2` for PPM*) |
+| `Sbus` | SBUS (UART2) | Dedicated pad for SBUS (*duplicate pad of `RX2` with signal inverter*) |
| `RX3, TX3` | UART3 | |
| `RX4, TX4` | UART4 | |
| `RX5, TX5` | UART5 | |
-| `RX5` | UART5-RX | (One per board corner) Duplicates of RX5 pad for ESC Telemetry |
+| `RX5` | UART5-RX | (*One per board corner*) Duplicates of RX5 pad for ESC Telemetry |
### UARTs + VCP
diff --git a/make/tools.mk b/make/tools.mk
index d29e8d47d2..52d71adb26 100644
--- a/make/tools.mk
+++ b/make/tools.mk
@@ -18,6 +18,11 @@ ARM_SDK_DIR ?= $(TOOLS_DIR)/gcc-arm-none-eabi-7-2017-q4-major
# Checked below, Should match the output of $(shell arm-none-eabi-gcc -dumpversion)
GCC_REQUIRED_VERSION ?= 7.2.1
+.PHONY: arm_sdk_version
+
+arm_sdk_version:
+ $(V1) $(ARM_SDK_PREFIX)gcc --version
+
## arm_sdk_install : Install Arm SDK
.PHONY: arm_sdk_install
diff --git a/src/main/build/debug.c b/src/main/build/debug.c
index bc8556077f..9ad6d60404 100644
--- a/src/main/build/debug.c
+++ b/src/main/build/debug.c
@@ -68,4 +68,5 @@ const char * const debugModeNames[DEBUG_COUNT] = {
"CURRENT_SENSOR",
"USB",
"SMARTAUDIO",
+ "RTH",
};
diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c
index 5be3af705e..6e0aaaa35a 100644
--- a/src/main/drivers/flash_m25p16.c
+++ b/src/main/drivers/flash_m25p16.c
@@ -61,6 +61,7 @@
#define JEDEC_ID_MICRON_N25Q064 0x20BA17
#define JEDEC_ID_MICRON_N25Q128 0x20ba18
#define JEDEC_ID_WINBOND_W25Q16 0xEF4015
+#define JEDEC_ID_WINBOND_W25Q32 0xEF4016
#define JEDEC_ID_WINBOND_W25Q64 0xEF4017
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
#define JEDEC_ID_CYPRESS_S25FL128L 0x016018
@@ -165,6 +166,7 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID)
fdevice->geometry.sectors = 32;
fdevice->geometry.pagesPerSector = 256;
break;
+ case JEDEC_ID_WINBOND_W25Q32:
case JEDEC_ID_MACRONIX_MX25L3206E:
fdevice->geometry.sectors = 64;
fdevice->geometry.pagesPerSector = 256;
diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c
index 7c88bf57d9..7578b2ecb6 100644
--- a/src/main/drivers/pwm_output.c
+++ b/src/main/drivers/pwm_output.c
@@ -31,12 +31,12 @@
#include "timer.h"
#include "drivers/pwm_output.h"
-static FAST_RAM pwmWriteFn *pwmWrite;
-static FAST_RAM pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
-static FAST_RAM pwmCompleteWriteFn *pwmCompleteWrite = NULL;
+static FAST_RAM_ZERO_INIT pwmWriteFn *pwmWrite;
+static FAST_RAM_ZERO_INIT pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
+static FAST_RAM_ZERO_INIT pwmCompleteWriteFn *pwmCompleteWrite = NULL;
#ifdef USE_DSHOT
-FAST_RAM loadDmaBufferFn *loadDmaBuffer;
+FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer;
#endif
#ifdef USE_SERVOS
@@ -51,7 +51,7 @@ static uint16_t freqBeep = 0;
static bool pwmMotorsEnabled = false;
static bool isDshot = false;
#ifdef USE_DSHOT_DMAR
-FAST_RAM bool useBurstDshot = false;
+FAST_RAM_ZERO_INIT bool useBurstDshot = false;
#endif
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
diff --git a/src/main/drivers/pwm_output_dshot_hal.c b/src/main/drivers/pwm_output_dshot_hal.c
index 74e6306e99..8e36a8ebd7 100644
--- a/src/main/drivers/pwm_output_dshot_hal.c
+++ b/src/main/drivers/pwm_output_dshot_hal.c
@@ -33,9 +33,9 @@
#include "dma.h"
#include "rcc.h"
-static FAST_RAM uint8_t dmaMotorTimerCount = 0;
-static FAST_RAM motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
-static FAST_RAM motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
+static FAST_RAM_ZERO_INIT uint8_t dmaMotorTimerCount = 0;
+static FAST_RAM_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
+static FAST_RAM_ZERO_INIT motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
motorDmaOutput_t *getMotorDmaOutput(uint8_t index)
{
diff --git a/src/main/drivers/serial_uart_pinconfig.c b/src/main/drivers/serial_uart_pinconfig.c
index 5b4c22f839..d9d6f9ad90 100644
--- a/src/main/drivers/serial_uart_pinconfig.c
+++ b/src/main/drivers/serial_uart_pinconfig.c
@@ -39,8 +39,8 @@
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
-FAST_RAM uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
-FAST_RAM uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
+FAST_RAM_ZERO_INIT uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
+FAST_RAM_ZERO_INIT uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
{
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index f31eb1652a..92552132a0 100644
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -928,8 +928,6 @@ static NOINLINE void subTaskMainSubprocesses(timeUs_t currentTimeUs)
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(throttleCorrectionConfig()->throttle_correction_value);
}
- processRcCommand();
-
#ifdef USE_SDCARD
afatfs_poll();
#endif
@@ -981,6 +979,12 @@ static void subTaskMotorUpdate(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime);
}
+static void subTaskRcCommand(timeUs_t currentTimeUs)
+{
+ processRcCommand();
+ UNUSED(currentTimeUs);
+}
+
// Function for loop trigger
FAST_CODE void taskMainPidLoop(timeUs_t currentTimeUs)
{
@@ -999,6 +1003,7 @@ FAST_CODE void taskMainPidLoop(timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_PIDLOOP, 0, micros() - currentTimeUs);
if (pidUpdateCounter++ % pidConfig()->pid_process_denom == 0) {
+ subTaskRcCommand(currentTimeUs);
subTaskPidController(currentTimeUs);
subTaskMotorUpdate(currentTimeUs);
subTaskMainSubprocesses(currentTimeUs);
diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h
index 14c02deb1d..95d9655857 100644
--- a/src/main/fc/fc_core.h
+++ b/src/main/fc/fc_core.h
@@ -47,7 +47,6 @@ void tryArm(void);
bool processRx(timeUs_t currentTimeUs);
void updateArmingStatus(void);
-void updateRcCommands(void);
void taskMainPidLoop(timeUs_t currentTimeUs);
bool isFlipOverAfterCrashMode(void);
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 4ddaf906d0..6eea859390 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -275,7 +275,7 @@ void init(void)
#endif
#ifdef USE_FAST_RAM
- /* Load FAST_RAM_INITIALIZED variable intializers into FAST RAM */
+ /* Load FAST_RAM variable intializers into DTCM RAM */
extern uint8_t _sfastram_data;
extern uint8_t _efastram_data;
extern uint8_t _sfastram_idata;
diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c
index 42077533fa..dde865ed27 100644
--- a/src/main/fc/rc_modes.c
+++ b/src/main/fc/rc_modes.c
@@ -42,7 +42,7 @@ boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
static bool modeChangesDisabled = false;
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions,
- PG_MODE_ACTIVATION_PROFILE, 0);
+ PG_MODE_ACTIVATION_PROFILE, 1);
bool IS_RC_MODE_ACTIVE(boxId_e boxId)
{
diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h
index 78661ecd23..2a2dafeca4 100644
--- a/src/main/fc/rc_modes.h
+++ b/src/main/fc/rc_modes.h
@@ -43,6 +43,8 @@ typedef enum {
BOXGPSRESCUE,
BOXID_FLIGHTMODE_LAST = BOXGPSRESCUE,
+// When new flight modes are added, the parameter group version for 'modeActivationConditions' in src/main/fc/rc_modes.c has to be incremented to ensure that the RC modes configuration is reset.
+
// RCMODE flags
BOXANTIGRAVITY,
BOXHEADADJ,
diff --git a/src/main/flight/gps_rescue.c b/src/main/flight/gps_rescue.c
index e78d0473c6..1f78f34643 100644
--- a/src/main/flight/gps_rescue.c
+++ b/src/main/flight/gps_rescue.c
@@ -164,7 +164,6 @@ void updateGPSRescueState(void)
}
newGPSData = false;
-
}
void sensorUpdate()
@@ -304,6 +303,7 @@ void rescueAttainPosition()
return;
}
+
/**
Speed controller
*/
@@ -364,7 +364,7 @@ void setBearing(int16_t deg)
dif *= -GET_DIRECTION(rcControlsConfig()->yaw_control_reversed);
- rcCommand[YAW] -= dif * gpsRescue()->yawP / 4;
+ rcCommand[YAW] = - (dif * gpsRescue()->yawP / 20);
}
#endif
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index af857fe772..bc4d94764e 100644
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -115,10 +115,10 @@ PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer, PG_MOTOR
#define PWM_RANGE_MID 1500
-static FAST_RAM uint8_t motorCount;
-static FAST_RAM float motorMixRange;
+static FAST_RAM_ZERO_INIT uint8_t motorCount;
+static FAST_RAM_ZERO_INIT float motorMixRange;
-float FAST_RAM motor[MAX_SUPPORTED_MOTORS];
+float FAST_RAM_ZERO_INIT motor[MAX_SUPPORTED_MOTORS];
float motor_disarmed[MAX_SUPPORTED_MOTORS];
mixerMode_e currentMixerMode;
@@ -313,12 +313,12 @@ const mixer_t mixers[] = {
};
#endif // !USE_QUAD_MIXER_ONLY
-FAST_RAM float motorOutputHigh, motorOutputLow;
+FAST_RAM_ZERO_INIT float motorOutputHigh, motorOutputLow;
-static FAST_RAM float disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
-static FAST_RAM uint16_t rcCommand3dDeadBandLow;
-static FAST_RAM uint16_t rcCommand3dDeadBandHigh;
-static FAST_RAM float rcCommandThrottleRange, rcCommandThrottleRange3dLow, rcCommandThrottleRange3dHigh;
+static FAST_RAM_ZERO_INIT float disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
+static FAST_RAM_ZERO_INIT uint16_t rcCommand3dDeadBandLow;
+static FAST_RAM_ZERO_INIT uint16_t rcCommand3dDeadBandHigh;
+static FAST_RAM_ZERO_INIT float rcCommandThrottleRange, rcCommandThrottleRange3dLow, rcCommandThrottleRange3dHigh;
uint8_t getMotorCount(void)
{
@@ -519,12 +519,12 @@ void stopPwmAllMotors(void)
delayMicroseconds(1500);
}
-static FAST_RAM float throttle = 0;
-static FAST_RAM float motorOutputMin;
-static FAST_RAM float motorRangeMin;
-static FAST_RAM float motorRangeMax;
-static FAST_RAM float motorOutputRange;
-static FAST_RAM int8_t motorOutputMixSign;
+static FAST_RAM_ZERO_INIT float throttle = 0;
+static FAST_RAM_ZERO_INIT float motorOutputMin;
+static FAST_RAM_ZERO_INIT float motorRangeMin;
+static FAST_RAM_ZERO_INIT float motorRangeMax;
+static FAST_RAM_ZERO_INIT float motorOutputRange;
+static FAST_RAM_ZERO_INIT int8_t motorOutputMixSign;
static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
{
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index 10859b5dcc..0292d2c28e 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -56,14 +56,14 @@
#include "sensors/acceleration.h"
-FAST_RAM uint32_t targetPidLooptime;
-FAST_RAM pidAxisData_t pidData[XYZ_AXIS_COUNT];
+FAST_RAM_ZERO_INIT uint32_t targetPidLooptime;
+FAST_RAM_ZERO_INIT pidAxisData_t pidData[XYZ_AXIS_COUNT];
-static FAST_RAM bool pidStabilisationEnabled;
+static FAST_RAM_ZERO_INIT bool pidStabilisationEnabled;
-static FAST_RAM bool inCrashRecoveryMode = false;
+static FAST_RAM_ZERO_INIT bool inCrashRecoveryMode = false;
-static FAST_RAM float dT;
+static FAST_RAM_ZERO_INIT float dT;
PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 2);
@@ -162,7 +162,7 @@ void pidResetITerm(void)
}
}
-static FAST_RAM_INITIALIZED float itermAccelerator = 1.0f;
+static FAST_RAM float itermAccelerator = 1.0f;
void pidSetItermAccelerator(float newItermAccelerator)
{
@@ -189,14 +189,14 @@ typedef union dtermLowpass_u {
#endif
} dtermLowpass_t;
-static FAST_RAM filterApplyFnPtr dtermNotchApplyFn;
-static FAST_RAM biquadFilter_t dtermNotch[2];
-static FAST_RAM filterApplyFnPtr dtermLowpassApplyFn;
-static FAST_RAM dtermLowpass_t dtermLowpass[2];
-static FAST_RAM filterApplyFnPtr dtermLowpass2ApplyFn;
-static FAST_RAM pt1Filter_t dtermLowpass2[2];
-static FAST_RAM filterApplyFnPtr ptermYawLowpassApplyFn;
-static FAST_RAM pt1Filter_t ptermYawLowpass;
+static FAST_RAM_ZERO_INIT filterApplyFnPtr dtermNotchApplyFn;
+static FAST_RAM_ZERO_INIT biquadFilter_t dtermNotch[2];
+static FAST_RAM_ZERO_INIT filterApplyFnPtr dtermLowpassApplyFn;
+static FAST_RAM_ZERO_INIT dtermLowpass_t dtermLowpass[2];
+static FAST_RAM_ZERO_INIT filterApplyFnPtr dtermLowpass2ApplyFn;
+static FAST_RAM_ZERO_INIT pt1Filter_t dtermLowpass2[2];
+static FAST_RAM_ZERO_INIT filterApplyFnPtr ptermYawLowpassApplyFn;
+static FAST_RAM_ZERO_INIT pt1Filter_t ptermYawLowpass;
void pidInitFilters(const pidProfile_t *pidProfile)
{
@@ -289,25 +289,25 @@ typedef struct pidCoefficient_s {
float Kd;
} pidCoefficient_t;
-static FAST_RAM pidCoefficient_t pidCoefficient[3];
-static FAST_RAM float maxVelocity[3];
-static FAST_RAM float relaxFactor;
-static FAST_RAM float dtermSetpointWeight;
-static FAST_RAM float levelGain, horizonGain, horizonTransition, horizonCutoffDegrees, horizonFactorRatio;
-static FAST_RAM float ITermWindupPointInv;
-static FAST_RAM uint8_t horizonTiltExpertMode;
-static FAST_RAM timeDelta_t crashTimeLimitUs;
-static FAST_RAM timeDelta_t crashTimeDelayUs;
-static FAST_RAM int32_t crashRecoveryAngleDeciDegrees;
-static FAST_RAM float crashRecoveryRate;
-static FAST_RAM float crashDtermThreshold;
-static FAST_RAM float crashGyroThreshold;
-static FAST_RAM float crashSetpointThreshold;
-static FAST_RAM float crashLimitYaw;
-static FAST_RAM float itermLimit;
-FAST_RAM float throttleBoost;
+static FAST_RAM_ZERO_INIT pidCoefficient_t pidCoefficient[3];
+static FAST_RAM_ZERO_INIT float maxVelocity[3];
+static FAST_RAM_ZERO_INIT float relaxFactor;
+static FAST_RAM_ZERO_INIT float dtermSetpointWeight;
+static FAST_RAM_ZERO_INIT float levelGain, horizonGain, horizonTransition, horizonCutoffDegrees, horizonFactorRatio;
+static FAST_RAM_ZERO_INIT float ITermWindupPointInv;
+static FAST_RAM_ZERO_INIT uint8_t horizonTiltExpertMode;
+static FAST_RAM_ZERO_INIT timeDelta_t crashTimeLimitUs;
+static FAST_RAM_ZERO_INIT timeDelta_t crashTimeDelayUs;
+static FAST_RAM_ZERO_INIT int32_t crashRecoveryAngleDeciDegrees;
+static FAST_RAM_ZERO_INIT float crashRecoveryRate;
+static FAST_RAM_ZERO_INIT float crashDtermThreshold;
+static FAST_RAM_ZERO_INIT float crashGyroThreshold;
+static FAST_RAM_ZERO_INIT float crashSetpointThreshold;
+static FAST_RAM_ZERO_INIT float crashLimitYaw;
+static FAST_RAM_ZERO_INIT float itermLimit;
+FAST_RAM_ZERO_INIT float throttleBoost;
pt1Filter_t throttleLpf;
-static FAST_RAM bool itermRotation;
+static FAST_RAM_ZERO_INIT bool itermRotation;
void pidInitConfig(const pidProfile_t *pidProfile)
{
diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c
index 8525b0ee48..fc50aa3167 100644
--- a/src/main/interface/cli.c
+++ b/src/main/interface/cli.c
@@ -215,6 +215,42 @@ static const char * const *sensorHardwareNames[] = {
};
#endif // USE_SENSOR_NAMES
+static void backupPgConfig(const pgRegistry_t *pg)
+{
+ memcpy(pg->copy, pg->address, pg->size);
+}
+
+static void restorePgConfig(const pgRegistry_t *pg)
+{
+ memcpy(pg->address, pg->copy, pg->size);
+}
+
+static void backupConfigs(void)
+{
+ // make copies of configs to do differencing
+ PG_FOREACH(pg) {
+ backupPgConfig(pg);
+ }
+
+ configIsInCopy = true;
+}
+
+static void restoreConfigs(void)
+{
+ PG_FOREACH(pg) {
+ restorePgConfig(pg);
+ }
+
+ configIsInCopy = false;
+}
+
+static void backupAndResetConfigs(void)
+{
+ backupConfigs();
+ // reset all configs to defaults to do differencing
+ resetConfigs();
+}
+
static void cliPrint(const char *str)
{
while (*str) {
@@ -449,7 +485,11 @@ static uint16_t getValueOffset(const clivalue_t *value)
void *cliGetValuePointer(const clivalue_t *value)
{
const pgRegistry_t* rec = pgFind(value->pgn);
- return CONST_CAST(void *, rec->address + getValueOffset(value));
+ if (configIsInCopy) {
+ return CONST_CAST(void *, rec->copy + getValueOffset(value));
+ } else {
+ return CONST_CAST(void *, rec->address + getValueOffset(value));
+ }
}
const void *cliGetDefaultPointer(const clivalue_t *value)
@@ -908,6 +948,7 @@ static void printSerial(uint8_t dumpMask, const serialConfig_t *serialConfig, co
static void cliSerial(char *cmdline)
{
+ const char *format = "serial %d %d %ld %ld %ld %ld";
if (isEmpty(cmdline)) {
printSerial(DUMP_MASTER, serialConfig(), NULL);
return;
@@ -984,6 +1025,16 @@ static void cliSerial(char *cmdline)
}
memcpy(currentConfig, &portConfig, sizeof(portConfig));
+
+ cliDumpPrintLinef(0, false, format,
+ portConfig.identifier,
+ portConfig.functionMask,
+ baudRates[portConfig.msp_baudrateIndex],
+ baudRates[portConfig.gps_baudrateIndex],
+ baudRates[portConfig.telemetry_baudrateIndex],
+ baudRates[portConfig.blackbox_baudrateIndex]
+ );
+
}
#ifndef SKIP_SERIAL_PASSTHROUGH
@@ -1159,6 +1210,7 @@ static void printAdjustmentRange(uint8_t dumpMask, const adjustmentRange_t *adju
static void cliAdjustmentRange(char *cmdline)
{
+ const char *format = "adjrange %u %u %u %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;
@@ -1210,6 +1262,7 @@ static void cliAdjustmentRange(char *cmdline)
if (validArgumentCount != 6) {
memset(ar, 0, sizeof(adjustmentRange_t));
cliShowParseError();
+ return;
}
// Optional arguments
@@ -1228,6 +1281,18 @@ static void cliAdjustmentRange(char *cmdline)
ar->adjustmentScale = val;
validArgumentCount++;
}
+ cliDumpPrintLinef(0, false, format,
+ i,
+ ar->adjustmentIndex,
+ ar->auxChannelIndex,
+ MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
+ MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
+ ar->adjustmentFunction,
+ ar->auxSwitchChannelIndex,
+ ar->adjustmentCenter,
+ ar->adjustmentScale
+ );
+
} else {
cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
}
@@ -1367,6 +1432,7 @@ static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channel
static void cliRxRange(char *cmdline)
{
+ const char *format = "rxrange %u %u %u";
int i, validArgumentCount = 0;
const char *ptr;
@@ -1400,6 +1466,12 @@ static void cliRxRange(char *cmdline)
rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigsMutable(i);
channelRangeConfig->min = rangeMin;
channelRangeConfig->max = rangeMax;
+ cliDumpPrintLinef(0, false, format,
+ i,
+ channelRangeConfig->min,
+ channelRangeConfig->max
+ );
+
}
} else {
cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
@@ -1429,6 +1501,8 @@ static void printLed(uint8_t dumpMask, const ledConfig_t *ledConfigs, const ledC
static void cliLed(char *cmdline)
{
+ const char *format = "led %u %s";
+ char ledConfigBuffer[20];
int i;
const char *ptr;
@@ -1439,7 +1513,10 @@ static void cliLed(char *cmdline)
i = atoi(ptr);
if (i < LED_MAX_STRIP_LENGTH) {
ptr = nextArg(cmdline);
- if (!parseLedStripConfig(i, ptr)) {
+ if (parseLedStripConfig(i, ptr)) {
+ generateLedConfig((ledConfig_t *)&ledStripConfig()->ledConfigs[i], ledConfigBuffer, sizeof(ledConfigBuffer));
+ cliDumpPrintLinef(0, false, format, i, ledConfigBuffer);
+ } else {
cliShowParseError();
}
} else {
@@ -1467,6 +1544,7 @@ static void printColor(uint8_t dumpMask, const hsvColor_t *colors, const hsvColo
static void cliColor(char *cmdline)
{
+ const char *format = "color %u %d,%u,%u";
if (isEmpty(cmdline)) {
printColor(DUMP_MASTER, ledStripConfig()->colors, NULL);
} else {
@@ -1474,7 +1552,10 @@ static void cliColor(char *cmdline)
const int i = atoi(ptr);
if (i < LED_CONFIGURABLE_COLOR_COUNT) {
ptr = nextArg(cmdline);
- if (!parseColor(i, ptr)) {
+ if (parseColor(i, ptr)) {
+ const hsvColor_t *color = &ledStripConfig()->colors[i];
+ cliDumpPrintLinef(0, false, format, i, color->h, color->s, color->v);
+ } else {
cliShowParseError();
}
} else {
@@ -1614,6 +1695,7 @@ static void printServo(uint8_t dumpMask, const servoParam_t *servoParams, const
static void cliServo(char *cmdline)
{
+ const char *format = "servo %u %d %d %d %d %d";
enum { SERVO_ARGUMENT_COUNT = 6 };
int16_t arguments[SERVO_ARGUMENT_COUNT];
@@ -1681,6 +1763,16 @@ static void cliServo(char *cmdline)
servo->middle = arguments[MIDDLE];
servo->rate = arguments[RATE];
servo->forwardFromChannel = arguments[FORWARD];
+
+ cliDumpPrintLinef(0, false, format,
+ i,
+ servo->min,
+ servo->max,
+ servo->middle,
+ servo->rate,
+ servo->forwardFromChannel
+ );
+
}
}
#endif
@@ -2050,6 +2142,7 @@ static void printVtx(uint8_t dumpMask, const vtxConfig_t *vtxConfig, const vtxCo
static void cliVtx(char *cmdline)
{
+ const char *format = "vtx %u %u %u %u %u %u";
int i, val = 0;
const char *ptr;
@@ -2091,6 +2184,16 @@ static void cliVtx(char *cmdline)
if (validArgumentCount != 5) {
memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
+ cliShowParseError();
+ } else {
+ cliDumpPrintLinef(0, false, format,
+ i,
+ cac->auxChannelIndex,
+ cac->band,
+ cac->channel,
+ MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
+ MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
+ );
}
} else {
cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
@@ -2370,11 +2473,20 @@ static void cliMap(char *cmdline)
cliPrintLinef("map %s", buf);
}
+static char *skipSpace(char *buffer)
+{
+ while (*(buffer) == ' ') {
+ buffer++;
+ }
+
+ return buffer;
+}
+
static char *checkCommand(char *cmdLine, const char *command)
{
if (!strncasecmp(cmdLine, command, strlen(command)) // command names match
&& (isspace((unsigned)cmdLine[strlen(command)]) || cmdLine[strlen(command)] == 0)) {
- return cmdLine + strlen(command) + 1;
+ return skipSpace(cmdLine + strlen(command) + 1);
} else {
return 0;
}
@@ -3003,24 +3115,44 @@ static void cliDefaults(char *cmdline)
}
}
+void cliPrintVarDefault(const clivalue_t *value)
+{
+ const pgRegistry_t *pg = pgFind(value->pgn);
+ if (pg) {
+ const char *defaultFormat = "Default value: ";
+ const int valueOffset = getValueOffset(value);
+ const bool equalsDefault = valuePtrEqualsDefault(value, pg->copy + valueOffset, pg->address + valueOffset);
+ if (!equalsDefault) {
+ cliPrintf(defaultFormat, value->name);
+ printValuePointer(value, (uint8_t*)pg->address + valueOffset, false);
+ cliPrintLinefeed();
+ }
+ }
+}
+
STATIC_UNIT_TESTED void cliGet(char *cmdline)
{
const clivalue_t *val;
int matchedCommands = 0;
+ backupAndResetConfigs();
+
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
if (strcasestr(valueTable[i].name, cmdline)) {
val = &valueTable[i];
+ if (matchedCommands > 0) {
+ cliPrintLinefeed();
+ }
cliPrintf("%s = ", valueTable[i].name);
cliPrintVar(val, 0);
cliPrintLinefeed();
cliPrintVarRange(val);
- cliPrintLinefeed();
-
+ cliPrintVarDefault(val);
matchedCommands++;
}
}
+ restoreConfigs();
if (matchedCommands) {
return;
@@ -3029,15 +3161,6 @@ STATIC_UNIT_TESTED void cliGet(char *cmdline)
cliPrintLine("Invalid name");
}
-static char *skipSpace(char *buffer)
-{
- while (*(buffer) == ' ') {
- buffer++;
- }
-
- return buffer;
-}
-
static uint8_t getWordLength(char *bufBegin, char *bufEnd)
{
while (*(bufEnd - 1) == ' ') {
@@ -3437,6 +3560,9 @@ const cliResourceValue_t resourceTable[] = {
#endif
#ifdef USE_MAG
DEFS( OWNER_COMPASS_CS, PG_COMPASS_CONFIG, compassConfig_t, mag_spi_csn ),
+#ifdef USE_MAG_DATA_READY_SIGNAL
+ DEFS( OWNER_COMPASS_EXTI, PG_COMPASS_CONFIG, compassConfig_t, interruptTag ),
+#endif
#endif
#ifdef USE_SDCARD
DEFS( OWNER_SDCARD_CS, PG_SDCARD_CONFIG, sdcardConfig_t, chipSelectTag ),
@@ -3804,25 +3930,6 @@ error:
}
#endif
-static void backupConfigs(void)
-{
- // make copies of configs to do differencing
- PG_FOREACH(pg) {
- memcpy(pg->copy, pg->address, pg->size);
- }
-
- configIsInCopy = true;
-}
-
-static void restoreConfigs(void)
-{
- PG_FOREACH(pg) {
- memcpy(pg->address, pg->copy, pg->size);
- }
-
- configIsInCopy = false;
-}
-
static void printConfig(char *cmdline, bool doDiff)
{
uint8_t dumpMask = DUMP_MASTER;
@@ -3842,14 +3949,8 @@ static void printConfig(char *cmdline, bool doDiff)
if (doDiff) {
dumpMask = dumpMask | DO_DIFF;
}
-
- backupConfigs();
- // reset all configs to defaults to do differencing
- resetConfigs();
-
-#if defined(USE_TARGET_CONFIG)
- targetConfiguration();
-#endif
+
+ backupAndResetConfigs();
if (checkCommand(options, "defaults")) {
dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
}
diff --git a/src/main/interface/msp_box.c b/src/main/interface/msp_box.c
index b3639ee95f..0060f87db7 100644
--- a/src/main/interface/msp_box.c
+++ b/src/main/interface/msp_box.c
@@ -196,6 +196,7 @@ void initActiveBoxIds(void)
if (feature(FEATURE_GPS)) {
BME(BOXGPSHOME);
BME(BOXGPSHOLD);
+ BME(BOXGPSRESCUE);
BME(BOXBEEPGPSCOUNT);
}
#endif
diff --git a/src/main/io/gps.c b/src/main/io/gps.c
index d7a3c38a0c..f5732a661a 100644
--- a/src/main/io/gps.c
+++ b/src/main/io/gps.c
@@ -243,7 +243,7 @@ PG_RESET_TEMPLATE(gpsRescue_t, gpsRescue,
.velP = 80,
.velI = 20,
.velD = 15,
- .yawP = 15,
+ .yawP = 40,
.throttleMin = 1200,
.throttleMax = 1600,
.throttleHover = 1280,
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index b3a85f1b0f..b8b4fd5b23 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -548,6 +548,8 @@ static bool osdDrawSingleElement(uint8_t item)
strcpy(buff, "STAB");
} else if (FLIGHT_MODE(HORIZON_MODE)) {
strcpy(buff, "HOR ");
+ } else if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
+ strcpy(buff, "RESC");
} else if (isAirmodeActive()) {
strcpy(buff, "AIR ");
} else {
diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c
index 3e2071322b..d5ea17b74e 100644
--- a/src/main/scheduler/scheduler.c
+++ b/src/main/scheduler/scheduler.c
@@ -45,21 +45,21 @@
// 2 - time spent in scheduler
// 3 - time spent executing check function
-static FAST_RAM cfTask_t *currentTask = NULL;
+static FAST_RAM_ZERO_INIT cfTask_t *currentTask = NULL;
-static FAST_RAM uint32_t totalWaitingTasks;
-static FAST_RAM uint32_t totalWaitingTasksSamples;
+static FAST_RAM_ZERO_INIT uint32_t totalWaitingTasks;
+static FAST_RAM_ZERO_INIT uint32_t totalWaitingTasksSamples;
-static FAST_RAM bool calculateTaskStatistics;
-FAST_RAM uint16_t averageSystemLoadPercent = 0;
+static FAST_RAM_ZERO_INIT bool calculateTaskStatistics;
+FAST_RAM_ZERO_INIT uint16_t averageSystemLoadPercent = 0;
-static FAST_RAM int taskQueuePos = 0;
-STATIC_UNIT_TESTED FAST_RAM int taskQueueSize = 0;
+static FAST_RAM_ZERO_INIT int taskQueuePos = 0;
+STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT int taskQueueSize = 0;
// No need for a linked list for the queue, since items are only inserted at startup
-STATIC_UNIT_TESTED FAST_RAM cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
+STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT cfTask_t* taskQueueArray[TASK_COUNT + 1]; // extra item for NULL pointer at end of queue
void queueClear(void)
{
diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c
index ea2e589bcd..c1616fca0c 100644
--- a/src/main/sensors/acceleration.c
+++ b/src/main/sensors/acceleration.c
@@ -82,7 +82,7 @@
#endif
-FAST_RAM acc_t acc; // acc access functions
+FAST_RAM_ZERO_INIT acc_t acc; // acc access functions
static float accumulatedMeasurements[XYZ_AXIS_COUNT];
static int accumulatedMeasurementCount;
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index 501afad692..9af0a71ef5 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -83,18 +83,18 @@
#define USE_GYRO_SLEW_LIMITER
#endif
-FAST_RAM gyro_t gyro;
-static FAST_RAM uint8_t gyroDebugMode;
+FAST_RAM_ZERO_INIT gyro_t gyro;
+static FAST_RAM_ZERO_INIT uint8_t gyroDebugMode;
static uint8_t gyroToUse = 0;
#ifdef USE_GYRO_OVERFLOW_CHECK
-static FAST_RAM uint8_t overflowAxisMask;
+static FAST_RAM_ZERO_INIT uint8_t overflowAxisMask;
#endif
-static FAST_RAM float accumulatedMeasurements[XYZ_AXIS_COUNT];
-static FAST_RAM float gyroPrevious[XYZ_AXIS_COUNT];
-static FAST_RAM timeUs_t accumulatedMeasurementTimeUs;
-static FAST_RAM timeUs_t accumulationLastTimeSampledUs;
+static FAST_RAM_ZERO_INIT float accumulatedMeasurements[XYZ_AXIS_COUNT];
+static FAST_RAM_ZERO_INIT float gyroPrevious[XYZ_AXIS_COUNT];
+static FAST_RAM_ZERO_INIT timeUs_t accumulatedMeasurementTimeUs;
+static FAST_RAM_ZERO_INIT timeUs_t accumulationLastTimeSampledUs;
static bool gyroHasOverflowProtection = true;
@@ -152,9 +152,9 @@ typedef struct gyroSensor_s {
} gyroSensor_t;
-STATIC_UNIT_TESTED FAST_RAM gyroSensor_t gyroSensor1;
+STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor1;
#ifdef USE_DUAL_GYRO
-STATIC_UNIT_TESTED FAST_RAM gyroSensor_t gyroSensor2;
+STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor2;
#endif
#ifdef UNIT_TEST
diff --git a/src/main/sensors/gyroanalyse.c b/src/main/sensors/gyroanalyse.c
index 8059c6fa80..a5958894b3 100644
--- a/src/main/sensors/gyroanalyse.c
+++ b/src/main/sensors/gyroanalyse.c
@@ -57,27 +57,27 @@
#define BIQUAD_Q 1.0f / sqrtf(2.0f) // quality factor - butterworth
-static FAST_RAM uint16_t fftSamplingScale;
+static FAST_RAM_ZERO_INIT uint16_t fftSamplingScale;
// gyro data used for frequency analysis
-static float FAST_RAM gyroData[XYZ_AXIS_COUNT][FFT_WINDOW_SIZE];
+static float FAST_RAM_ZERO_INIT gyroData[XYZ_AXIS_COUNT][FFT_WINDOW_SIZE];
-static FAST_RAM arm_rfft_fast_instance_f32 fftInstance;
-static FAST_RAM float fftData[FFT_WINDOW_SIZE];
-static FAST_RAM float rfftData[FFT_WINDOW_SIZE];
-static FAST_RAM gyroFftData_t fftResult[XYZ_AXIS_COUNT];
+static FAST_RAM_ZERO_INIT arm_rfft_fast_instance_f32 fftInstance;
+static FAST_RAM_ZERO_INIT float fftData[FFT_WINDOW_SIZE];
+static FAST_RAM_ZERO_INIT float rfftData[FFT_WINDOW_SIZE];
+static FAST_RAM_ZERO_INIT gyroFftData_t fftResult[XYZ_AXIS_COUNT];
// use a circular buffer for the last FFT_WINDOW_SIZE samples
-static FAST_RAM uint16_t fftIdx;
+static FAST_RAM_ZERO_INIT uint16_t fftIdx;
// bandpass filter gyro data
-static FAST_RAM biquadFilter_t fftGyroFilter[XYZ_AXIS_COUNT];
+static FAST_RAM_ZERO_INIT biquadFilter_t fftGyroFilter[XYZ_AXIS_COUNT];
// filter for smoothing frequency estimation
-static FAST_RAM biquadFilter_t fftFreqFilter[XYZ_AXIS_COUNT];
+static FAST_RAM_ZERO_INIT biquadFilter_t fftFreqFilter[XYZ_AXIS_COUNT];
// Hanning window, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window
-static FAST_RAM float hanningWindow[FFT_WINDOW_SIZE];
+static FAST_RAM_ZERO_INIT float hanningWindow[FFT_WINDOW_SIZE];
void initHanning(void)
{
@@ -128,10 +128,10 @@ const gyroFftData_t *gyroFftData(int axis)
void gyroDataAnalyse(const gyroDev_t *gyroDev, biquadFilter_t *notchFilterDyn)
{
// accumulator for oversampled data => no aliasing and less noise
- static FAST_RAM float fftAcc[XYZ_AXIS_COUNT];
- static FAST_RAM uint32_t fftAccCount;
+ static FAST_RAM_ZERO_INIT float fftAcc[XYZ_AXIS_COUNT];
+ static FAST_RAM_ZERO_INIT uint32_t fftAccCount;
- static FAST_RAM uint32_t gyroDataAnalyseUpdateTicks;
+ static FAST_RAM_ZERO_INIT uint32_t gyroDataAnalyseUpdateTicks;
// if gyro sampling is > 1kHz, accumulate multiple samples
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
diff --git a/src/main/target/BETAFLIGHTF4/target.mk b/src/main/target/BETAFLIGHTF4/target.mk
index 0db7894474..59f3ba282b 100644
--- a/src/main/target/BETAFLIGHTF4/target.mk
+++ b/src/main/target/BETAFLIGHTF4/target.mk
@@ -1,6 +1,6 @@
F405_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
+FEATURES += VCP ONBOARDFLASH SDCARD
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
diff --git a/src/main/target/CLRACINGF7/CL_RACINGF7.md b/src/main/target/CLRACINGF7/CL_RACINGF7.md
index a7ed8267d5..ab6f092224 100644
--- a/src/main/target/CLRACINGF7/CL_RACINGF7.md
+++ b/src/main/target/CLRACINGF7/CL_RACINGF7.md
@@ -1,9 +1,9 @@
MCU: STM32F722RE
-IMU: MPU-6000
+IMU: ICM-20602
IMU Interrupt: yes
BARO: NO
VCP: YES
-Hardware UARTS:
+Hardware UARTS: 6 uarts
OSD: uses a AB7456 chip
Blackbox: SD Card
PPM/UART NOT Shared: YES
diff --git a/src/main/target/CLRACINGF7/target.c b/src/main/target/CLRACINGF7/target.c
index ebc6e9ba39..b2e89979f4 100644
--- a/src/main/target/CLRACINGF7/target.c
+++ b/src/main/target/CLRACINGF7/target.c
@@ -17,7 +17,6 @@
*
* If not, see .
*/
-
#include
#include
@@ -27,20 +26,16 @@
#include "drivers/timer.h"
#include "drivers/timer_def.h"
-// DSHOT will work for motor 1-6.
-
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM10, CH1, PB8, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
- DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // PWM1 - DMA1_ST6 D(1, 7, 3),D(1, 6, 3)
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // PWM2 - DMA2_ST2 D(2, 4, 7),D(2, 2, 0)
- DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // PWM3 - DMA1_ST1 D(1, 1, 3)
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // PWM4 - DMA1_ST2 D(1, 2, 5)
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 2), // PWM5 - DMA2_ST3 D(2, 6, 0),D(2, 1, 6),D(2, 3, 6)
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // PWM6 - DMA1_ST0 D(1, 0, 2)
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST6
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST6
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST6
+ DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // D1-ST6
- DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S5_OUT - DMA2_ST6 D(2, 6, 0),D(2, 6, 6)
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2
};
diff --git a/src/main/target/CLRACINGF7/target.h b/src/main/target/CLRACINGF7/target.h
index ab3673daba..bae20e3641 100644
--- a/src/main/target/CLRACINGF7/target.h
+++ b/src/main/target/CLRACINGF7/target.h
@@ -20,32 +20,21 @@
#pragma once
#define TARGET_BOARD_IDENTIFIER "CLR7"
-
#define USBD_PRODUCT_STRING "CLRACINGF7"
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PB0
#define USE_BEEPER
-#define BEEPER_PIN PB4
+#define BEEPER_PIN PB4
#define BEEPER_INVERTED
//define camera control
-#define CAMERA_CONTROL_PIN PB8
+#define CAMERA_CONTROL_PIN PB3
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
-//ICM20689
-#define ICM20689_CS_PIN PA4
-#define ICM20689_SPI_INSTANCE SPI1
-#define USE_GYRO
-#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW0_DEG
-#define USE_ACC
-#define USE_ACC_SPI_ICM20689
-#define ACC_ICM20689_ALIGN CW0_DEG
-
//MPU-6000
#define USE_ACC
#define USE_ACC_SPI_MPU6000
@@ -73,24 +62,33 @@
#define MAX7456_SPI_CS_PIN PA15
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
+//define use flash
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+//define use SD card
#define USE_SDCARD
-#define SDCARD_DETECT_PIN PB7
+#define SDCARD_DETECT_PIN PA8
#define SDCARD_SPI_INSTANCE SPI2
-#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
-
+#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
// Divide to under 25MHz for normal operation:
-#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
-
+#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
#define SDCARD_DMA_CHANNEL 0
#define USE_VCP
+
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
+#define USE_UART2
+#define UART2_RX_PIN PA3
+#define UART2_TX_PIN PA2
+
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
@@ -99,39 +97,39 @@
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
+#define USE_UART5
+#define UART5_RX_PIN PD2
+#define UART5_TX_PIN PC12
+
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
-#define USE_SOFTSERIAL1
-
-#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3,USART4, USART6, SOFT_SERIAL1
+//#define USE_SOFTSERIAL1
+#define SERIAL_PORT_COUNT 7 //VCP, USART1, USART2,USART3,USART4,USART5,USART6
#define USE_ESCSERIAL
#define ESCSERIAL_TIMER_TX_PIN PB8 // (Hardware=0, PPM)
-// XXX To target maintainer: Bus device to configure must be specified.
-//#define USE_I2C
-
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3
-#define SPI1_NSS_PIN PA4
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
+#define SPI1_NSS_PIN PA4
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
+#define SPI2_NSS_PIN PB12
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
-#define SPI3_NSS_PIN PA15
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PC12
+#define SPI3_NSS_PIN PA15
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
#define USE_ADC
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
@@ -142,17 +140,16 @@
#define CURRENT_METER_SCALE_DEFAULT 250 // 3.3/120A = 25mv/A
#define BINDPLUG_PIN PB2
-#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_UART SERIAL_PORT_USART6
-#define TELEMETRY_UART SERIAL_PORT_USART1
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+#define SERIALRX_UART SERIAL_PORT_UART5
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(10) )
+#define USABLE_TIMER_CHANNEL_COUNT 6
+#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/CLRACINGF7/target.mk b/src/main/target/CLRACINGF7/target.mk
index ab85a4ba98..2f2f023cd6 100644
--- a/src/main/target/CLRACINGF7/target.mk
+++ b/src/main/target/CLRACINGF7/target.mk
@@ -1,12 +1,10 @@
F7X2RE_TARGETS += $(TARGET)
-FEATURES += SDCARD VCP
+FEATURES += VCP ONBOARDFLASH SDCARD
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_icm20689.c\
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
drivers/max7456.c
-
diff --git a/src/main/target/FOXEERF405/target.c b/src/main/target/FOXEERF405/target.c
new file mode 100644
index 0000000000..dc48fd930e
--- /dev/null
+++ b/src/main/target/FOXEERF405/target.c
@@ -0,0 +1,45 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software under the terms of the
+ * GNU General Public License as published by the Free Software
+ * Foundation, either version 3 of the License, or (at your option)
+ * any later version.
+ *
+ * Cleanflight and Betaflight are distributed in the hope that they
+ * will be useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this software.
+ *
+ * If not, see .
+ */
+
+#include
+
+#include
+#include "drivers/io.h"
+
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
+
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1 (1,7)
+ DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S2 (1,4)
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S3 (2,4)
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S4 (2,7)
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S5 (2,2)
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S6 (2,3)
+
+
+ DEF_TIM(TIM1, CH3, PA10, TIM_USE_LED, 0, 0), // LED STRIP(2,6)
+
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM, 0, 0), // FC CAM
+
+};
diff --git a/src/main/target/FOXEERF405/target.h b/src/main/target/FOXEERF405/target.h
new file mode 100644
index 0000000000..f627c18782
--- /dev/null
+++ b/src/main/target/FOXEERF405/target.h
@@ -0,0 +1,164 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software under the terms of the
+ * GNU General Public License as published by the Free Software
+ * Foundation, either version 3 of the License, or (at your option)
+ * any later version.
+ *
+ * Cleanflight and Betaflight are distributed in the hope that they
+ * will be useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "FXF4"
+#define USBD_PRODUCT_STRING "FOXEERF405"
+//----------------------------------------
+
+//LED & BEE-------------------------------
+#define LED0_PIN PC15
+
+#define USE_BEEPER
+#define BEEPER_PIN PA4
+#define BEEPER_INVERTED
+
+//define camera control
+#define CAMERA_CONTROL_PIN PB3
+
+//Gyro & ACC-------------------------------
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_EXTI
+#define MPU_INT_EXTI PC4
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define USE_GYRO
+#define USE_ACC
+//------ICM20689
+#define ICM20689_CS_PIN PB2
+#define ICM20689_SPI_INSTANCE SPI1
+
+#define USE_GYRO_SPI_ICM20689
+#define GYRO_ICM20689_ALIGN CW90_DEG
+
+#define USE_ACC_SPI_ICM20689
+#define ACC_ICM20689_ALIGN CW90_DEG
+//------MPU6000
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW90_DEG
+
+#define USE_ACC_SPI_MPU6000
+#define ACC_MPU6000_ALIGN CW90_DEG
+
+//Baro & MAG-------------------------------
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+//ON BOARD FLASH -----------------------------------
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PC3
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+
+//GPS ----------------------------------------------
+#define USE_GPS
+#define USE_GPS_UBLOX
+#define USE_GPS_NMEA
+//OSD ----------------------------------------------
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define USE_OSD
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI3
+#define MAX7456_SPI_CS_PIN PA15
+
+//UART ----------------------------------------------
+#define USE_VCP
+
+#define USE_UART1
+#define UART1_RX_PIN PB7
+#define UART1_TX_PIN PA9
+
+#define USE_UART2
+#define UART2_RX_PIN PA3
+#define UART2_TX_PIN PA2
+
+#define USE_UART3
+#define UART3_RX_PIN PB11
+#define UART3_TX_PIN PB10
+
+#define USE_UART4
+#define UART4_RX_PIN PA1
+#define UART4_TX_PIN PA0
+
+#define USE_UART5
+#define UART5_RX_PIN PD2
+#define UART5_TX_PIN PC12
+
+#define USE_SOFTSERIAL1
+#define USE_SOFTSERIAL2
+
+#define SERIAL_PORT_COUNT 8
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+
+//ADC ----------------------------------------------
+#define USE_ADC
+#define ADC1_DMA_STREAM DMA2_Stream0
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define RSSI_ADC_PIN PA0 //TIM5_CH1 & UART4_TX & TELEMETRY & FPORT
+
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+
+#define CURRENT_METER_SCALE_DEFAULT 166
+
+#define ENABLE_DSHOT_DMAR true
+
+#define USE_ESCSERIAL
+#define ESCSERIAL_TIMER_TX_PIN PA3
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD (BIT(2))
+
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(8)|TIM_N(12))
+
+
+
diff --git a/src/main/target/FOXEERF405/target.mk b/src/main/target/FOXEERF405/target.mk
new file mode 100644
index 0000000000..4cf5fd8939
--- /dev/null
+++ b/src/main/target/FOXEERF405/target.mk
@@ -0,0 +1,11 @@
+F405_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+TARGET_SRC = \
+ drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/barometer/barometer_bmp085.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_ms5611.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/max7456.c
+
diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h
index 3e714192fc..bbcf6c6dc5 100644
--- a/src/main/target/common_fc_pre.h
+++ b/src/main/target/common_fc_pre.h
@@ -101,11 +101,11 @@
#endif // USE_ITCM_RAM
#ifdef USE_FAST_RAM
-#define FAST_RAM __attribute__ ((section(".fastram_bss"), aligned(4)))
-#define FAST_RAM_INITIALIZED __attribute__ ((section(".fastram_data"), aligned(4)))
+#define FAST_RAM_ZERO_INIT __attribute__ ((section(".fastram_bss"), aligned(4)))
+#define FAST_RAM __attribute__ ((section(".fastram_data"), aligned(4)))
#else
+#define FAST_RAM_ZERO_INIT
#define FAST_RAM
-#define FAST_RAM_INITIALIZED
#endif // USE_FAST_RAM
#ifdef STM32F4
diff --git a/src/main/target/common_osd_slave.h b/src/main/target/common_osd_slave.h
index 99988fda4b..1f155d940d 100644
--- a/src/main/target/common_osd_slave.h
+++ b/src/main/target/common_osd_slave.h
@@ -60,6 +60,7 @@
#endif
#define FAST_CODE
+#define FAST_RAM_ZERO_INIT
#define FAST_RAM
//CLI needs FC dependencies removed before we can compile it, disabling for now
diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c
index 1c4300781f..aca2877807 100644
--- a/src/main/telemetry/smartport.c
+++ b/src/main/telemetry/smartport.c
@@ -455,6 +455,13 @@ static void smartPortSendMspResponse(uint8_t *data) {
void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clearToSend, const uint32_t *requestTimeout)
{
+ static uint8_t smartPortIdCycleCnt = 0;
+ static uint8_t t1Cnt = 0;
+ static uint8_t t2Cnt = 0;
+#ifdef USE_ESC_SENSOR
+ static uint8_t smartPortIdOffset = 0;
+#endif
+
if (payload) {
// do not check the physical ID here again
// unless we start receiving other sensors' packets
@@ -493,18 +500,12 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
// we can send back any data we want, our tables keep track of the order and frequency of each data type we send
frSkyTableInfo_t * tableInfo = &frSkyDataIdTableInfo;
- static uint8_t smartPortIdCycleCnt = 0;
if (smartPortIdCycleCnt % SENSOR_REST_PERIOD == 0) {
-#ifdef USE_ESC_SENSOR
smartPortIdCycleCnt++;
-#else
- smartPortIdCycleCnt = 0;
-#endif
return;
}
#ifdef USE_ESC_SENSOR
- static uint8_t smartPortIdOffset = 0;
if (smartPortIdCycleCnt >= ESC_SENSOR_PERIOD) {
// send ESC sensors
tableInfo = &frSkyEscDataIdTableInfo;
@@ -520,9 +521,11 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
if (smartPortIdCycleCnt < ESC_SENSOR_PERIOD) {
// send other sensors
tableInfo = &frSkyDataIdTableInfo;
+#endif
if (tableInfo->index == tableInfo->size) { // end of table reached, loop back
tableInfo->index = 0;
}
+#ifdef USE_ESC_SENSOR
}
#endif
uint16_t id = tableInfo->table[tableInfo->index];
@@ -536,8 +539,6 @@ void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clear
int32_t tmpi;
uint32_t tmp2 = 0;
- static uint8_t t1Cnt = 0;
- static uint8_t t2Cnt = 0;
uint16_t vfasVoltage;
uint8_t cellCount;
diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h
index 633cf2dfce..940d771b68 100644
--- a/src/test/unit/platform.h
+++ b/src/test/unit/platform.h
@@ -27,8 +27,8 @@
#define NOINLINE
#define FAST_CODE
+#define FAST_RAM_ZERO_INIT
#define FAST_RAM
-#define FAST_RAM_INITIALIZED
#define MAX_PROFILE_COUNT 3
#define USE_MAG