mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 07:15:18 +03:00
Merge branch 'master' into bfdev-configurable-escserial-pin
This commit is contained in:
commit
5a7054f704
177 changed files with 1964 additions and 1338 deletions
10
.gitignore
vendored
10
.gitignore
vendored
|
@ -20,9 +20,9 @@ docs/Manual.pdf
|
||||||
README.pdf
|
README.pdf
|
||||||
|
|
||||||
# artefacts of top-level Makefile
|
# artefacts of top-level Makefile
|
||||||
/downloads
|
/downloads/
|
||||||
/tools
|
/tools/
|
||||||
/build
|
/build/
|
||||||
# local changes only
|
# local changes only
|
||||||
make/local.mk
|
make/local.mk
|
||||||
|
|
||||||
|
@ -32,8 +32,8 @@ mcu.mak.old
|
||||||
stm32.mak
|
stm32.mak
|
||||||
|
|
||||||
# artefacts for Visual Studio Code
|
# artefacts for Visual Studio Code
|
||||||
/.vscode
|
/.vscode/
|
||||||
|
|
||||||
# artefacts for CLion
|
# artefacts for CLion
|
||||||
/cmake-build-debug
|
/cmake-build-debug/
|
||||||
/CMakeLists.txt
|
/CMakeLists.txt
|
||||||
|
|
24
Makefile
24
Makefile
|
@ -842,23 +842,14 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||||
common/typeconversion.c \
|
common/typeconversion.c \
|
||||||
drivers/adc.c \
|
drivers/adc.c \
|
||||||
drivers/buf_writer.c \
|
drivers/buf_writer.c \
|
||||||
drivers/bus_i2c_soft.c \
|
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
drivers/bus_spi_soft.c \
|
|
||||||
drivers/exti.c \
|
drivers/exti.c \
|
||||||
drivers/gyro_sync.c \
|
drivers/gyro_sync.c \
|
||||||
drivers/io.c \
|
drivers/io.c \
|
||||||
drivers/light_led.c \
|
|
||||||
drivers/resource.c \
|
|
||||||
drivers/rx_nrf24l01.c \
|
|
||||||
drivers/rx_spi.c \
|
|
||||||
drivers/rx_xn297.c \
|
|
||||||
drivers/pwm_output.c \
|
drivers/pwm_output.c \
|
||||||
drivers/rcc.c \
|
drivers/rcc.c \
|
||||||
drivers/rx_pwm.c \
|
|
||||||
drivers/serial.c \
|
drivers/serial.c \
|
||||||
drivers/serial_uart.c \
|
drivers/serial_uart.c \
|
||||||
drivers/sound_beeper.c \
|
|
||||||
drivers/system.c \
|
drivers/system.c \
|
||||||
drivers/timer.c \
|
drivers/timer.c \
|
||||||
fc/fc_core.c \
|
fc/fc_core.c \
|
||||||
|
@ -869,16 +860,9 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||||
flight/imu.c \
|
flight/imu.c \
|
||||||
flight/mixer.c \
|
flight/mixer.c \
|
||||||
flight/pid.c \
|
flight/pid.c \
|
||||||
flight/servos.c \
|
|
||||||
io/serial.c \
|
io/serial.c \
|
||||||
rx/ibus.c \
|
rx/ibus.c \
|
||||||
rx/jetiexbus.c \
|
rx/jetiexbus.c \
|
||||||
rx/nrf24_cx10.c \
|
|
||||||
rx/nrf24_inav.c \
|
|
||||||
rx/nrf24_h8_3d.c \
|
|
||||||
rx/nrf24_syma.c \
|
|
||||||
rx/nrf24_v202.c \
|
|
||||||
rx/pwm.c \
|
|
||||||
rx/rx.c \
|
rx/rx.c \
|
||||||
rx/rx_spi.c \
|
rx/rx_spi.c \
|
||||||
rx/crsf.c \
|
rx/crsf.c \
|
||||||
|
@ -894,9 +878,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
||||||
sensors/gyroanalyse.c \
|
sensors/gyroanalyse.c \
|
||||||
$(CMSIS_SRC) \
|
$(CMSIS_SRC) \
|
||||||
$(DEVICE_STDPERIPH_SRC) \
|
$(DEVICE_STDPERIPH_SRC) \
|
||||||
drivers/display_ug2864hsweg01.c \
|
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
drivers/serial_softserial.c \
|
|
||||||
io/displayport_max7456.c \
|
io/displayport_max7456.c \
|
||||||
io/osd.c \
|
io/osd.c \
|
||||||
io/osd_slave.c
|
io/osd_slave.c
|
||||||
|
@ -1145,6 +1127,7 @@ endif
|
||||||
CROSS_CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
|
CROSS_CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
|
||||||
CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++
|
CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++
|
||||||
OBJCOPY := $(ARM_SDK_PREFIX)objcopy
|
OBJCOPY := $(ARM_SDK_PREFIX)objcopy
|
||||||
|
OBJDUMP := $(ARM_SDK_PREFIX)objdump
|
||||||
SIZE := $(ARM_SDK_PREFIX)size
|
SIZE := $(ARM_SDK_PREFIX)size
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -1269,6 +1252,7 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
|
||||||
TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
|
TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
|
||||||
TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
|
TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
|
||||||
TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
||||||
|
TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).lst
|
||||||
TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
||||||
TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
||||||
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||||
|
@ -1277,6 +1261,7 @@ TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||||
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
||||||
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
||||||
CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
|
CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
|
||||||
|
CLEAN_ARTIFACTS += $(TARGET_LST)
|
||||||
|
|
||||||
# Make sure build date and revision is updated on every incremental build
|
# Make sure build date and revision is updated on every incremental build
|
||||||
$(OBJECT_DIR)/$(TARGET)/build/version.o : $(SRC)
|
$(OBJECT_DIR)/$(TARGET)/build/version.o : $(SRC)
|
||||||
|
@ -1284,6 +1269,9 @@ $(OBJECT_DIR)/$(TARGET)/build/version.o : $(SRC)
|
||||||
# List of buildable ELF files and their object dependencies.
|
# List of buildable ELF files and their object dependencies.
|
||||||
# It would be nice to compute these lists, but that seems to be just beyond make.
|
# It would be nice to compute these lists, but that seems to be just beyond make.
|
||||||
|
|
||||||
|
$(TARGET_LST): $(TARGET_ELF)
|
||||||
|
$(V0) $(OBJDUMP) -S --disassemble $< > $@
|
||||||
|
|
||||||
$(TARGET_HEX): $(TARGET_ELF)
|
$(TARGET_HEX): $(TARGET_ELF)
|
||||||
$(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
|
$(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
|
||||||
|
|
||||||
|
|
11
Vagrantfile
vendored
11
Vagrantfile
vendored
|
@ -11,8 +11,12 @@ Vagrant.configure(2) do |config|
|
||||||
# https://docs.vagrantup.com.
|
# https://docs.vagrantup.com.
|
||||||
|
|
||||||
# Every Vagrant development environment requires a box. You can search for
|
# Every Vagrant development environment requires a box. You can search for
|
||||||
# boxes at https://atlas.hashicorp.com/search.
|
# boxes at https://app.vagrantup.com/boxes/search
|
||||||
config.vm.box = "ubuntu/trusty64"
|
config.vm.box = "ubuntu/xenial64"
|
||||||
|
|
||||||
|
config.vm.provider "virtualbox" do |v|
|
||||||
|
v.memory = 4096
|
||||||
|
end
|
||||||
|
|
||||||
# Enable provisioning with a shell script. Additional provisioners such as
|
# Enable provisioning with a shell script. Additional provisioners such as
|
||||||
# Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the
|
# Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the
|
||||||
|
@ -21,7 +25,8 @@ Vagrant.configure(2) do |config|
|
||||||
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi
|
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi
|
||||||
add-apt-repository ppa:team-gcc-arm-embedded/ppa
|
add-apt-repository ppa:team-gcc-arm-embedded/ppa
|
||||||
apt-get update
|
apt-get update
|
||||||
apt-get install -y git ccache gcc-arm-embedded=6-2017q1-1~trusty3
|
apt-get install -y git gcc-arm-embedded=6-2017q2-1~xenial1
|
||||||
|
apt-get install -y make python gcc clang
|
||||||
SHELL
|
SHELL
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
|
@ -622,9 +622,9 @@ void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi);
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/* I/O operation functions ***************************************************/
|
/* I/O operation functions ***************************************************/
|
||||||
HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, const uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||||
HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout);
|
||||||
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
|
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, const uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
|
||||||
uint32_t Timeout);
|
uint32_t Timeout);
|
||||||
HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
|
HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
|
||||||
HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
|
HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size);
|
||||||
|
|
|
@ -493,7 +493,7 @@ __weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi)
|
||||||
* @param Timeout: Timeout duration
|
* @param Timeout: Timeout duration
|
||||||
* @retval HAL status
|
* @retval HAL status
|
||||||
*/
|
*/
|
||||||
HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
|
HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, const uint8_t *pData, uint16_t Size, uint32_t Timeout)
|
||||||
{
|
{
|
||||||
uint32_t tickstart = 0U;
|
uint32_t tickstart = 0U;
|
||||||
HAL_StatusTypeDef errorcode = HAL_OK;
|
HAL_StatusTypeDef errorcode = HAL_OK;
|
||||||
|
@ -882,7 +882,7 @@ error :
|
||||||
* @param Timeout: Timeout duration
|
* @param Timeout: Timeout duration
|
||||||
* @retval HAL status
|
* @retval HAL status
|
||||||
*/
|
*/
|
||||||
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
|
HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, const uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
|
||||||
uint32_t Timeout)
|
uint32_t Timeout)
|
||||||
{
|
{
|
||||||
uint32_t tmp = 0U, tmp1 = 0U;
|
uint32_t tmp = 0U, tmp1 = 0U;
|
||||||
|
|
|
@ -134,7 +134,6 @@ static OSD_Entry menuMainEntries[] =
|
||||||
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
|
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
|
||||||
#ifdef OSD
|
#ifdef OSD
|
||||||
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
|
{"OSD", OME_Submenu, cmsMenuChange, &cmsx_menuOsd, 0},
|
||||||
{"ALARMS", OME_Submenu, cmsMenuChange, &cmsx_menuAlarms, 0},
|
|
||||||
#endif
|
#endif
|
||||||
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
|
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
|
||||||
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
|
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
|
||||||
|
|
|
@ -39,51 +39,6 @@
|
||||||
#include "io/displayport_max7456.h"
|
#include "io/displayport_max7456.h"
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
|
|
||||||
static uint8_t osdConfig_rssi_alarm;
|
|
||||||
static uint16_t osdConfig_cap_alarm;
|
|
||||||
static uint16_t osdConfig_time_alarm;
|
|
||||||
static uint16_t osdConfig_alt_alarm;
|
|
||||||
|
|
||||||
static long cmsx_menuAlarmsOnEnter(void)
|
|
||||||
{
|
|
||||||
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
|
||||||
osdConfig_cap_alarm = osdConfig()->cap_alarm;
|
|
||||||
osdConfig_time_alarm = osdConfig()->time_alarm;
|
|
||||||
osdConfig_alt_alarm = osdConfig()->alt_alarm;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
static long cmsx_menuAlarmsOnExit(const OSD_Entry *self)
|
|
||||||
{
|
|
||||||
UNUSED(self);
|
|
||||||
|
|
||||||
osdConfigMutable()->rssi_alarm = osdConfig_rssi_alarm;
|
|
||||||
osdConfigMutable()->cap_alarm = osdConfig_cap_alarm;
|
|
||||||
osdConfigMutable()->time_alarm = osdConfig_time_alarm;
|
|
||||||
osdConfigMutable()->alt_alarm = osdConfig_alt_alarm;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
OSD_Entry cmsx_menuAlarmsEntries[] =
|
|
||||||
{
|
|
||||||
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
|
||||||
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0},
|
|
||||||
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0},
|
|
||||||
{"FLY TIME", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_time_alarm, 1, 200, 1}, 0},
|
|
||||||
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0},
|
|
||||||
{"BACK", OME_Back, NULL, NULL, 0},
|
|
||||||
{NULL, OME_END, NULL, NULL, 0}
|
|
||||||
};
|
|
||||||
|
|
||||||
CMS_Menu cmsx_menuAlarms = {
|
|
||||||
.GUARD_text = "MENUALARMS",
|
|
||||||
.GUARD_type = OME_MENU,
|
|
||||||
.onEnter = cmsx_menuAlarmsOnEnter,
|
|
||||||
.onExit = cmsx_menuAlarmsOnExit,
|
|
||||||
.onGlobalExit = NULL,
|
|
||||||
.entries = cmsx_menuAlarmsEntries,
|
|
||||||
};
|
|
||||||
|
|
||||||
#ifndef DISABLE_EXTENDED_CMS_OSD_MENU
|
#ifndef DISABLE_EXTENDED_CMS_OSD_MENU
|
||||||
static uint16_t osdConfig_item_pos[OSD_ITEM_COUNT];
|
static uint16_t osdConfig_item_pos[OSD_ITEM_COUNT];
|
||||||
|
|
||||||
|
@ -111,8 +66,8 @@ OSD_Entry menuOsdActiveElemsEntries[] =
|
||||||
{"CROSSHAIRS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS], 0},
|
{"CROSSHAIRS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS], 0},
|
||||||
{"HORIZON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
{"HORIZON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
||||||
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HORIZON_SIDEBARS], 0},
|
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HORIZON_SIDEBARS], 0},
|
||||||
{"UPTIME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ONTIME], 0},
|
{"TIMER 1", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_TIMER_1], 0},
|
||||||
{"FLY TIME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLYTIME], 0},
|
{"TIMER 2", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_TIMER_2], 0},
|
||||||
{"FLY MODE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLYMODE], 0},
|
{"FLY MODE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLYMODE], 0},
|
||||||
{"NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CRAFT_NAME], 0},
|
{"NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CRAFT_NAME], 0},
|
||||||
{"THROTTLE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_THROTTLE_POS], 0},
|
{"THROTTLE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_THROTTLE_POS], 0},
|
||||||
|
@ -141,7 +96,6 @@ OSD_Entry menuOsdActiveElemsEntries[] =
|
||||||
{"DISARMED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_DISARMED], 0},
|
{"DISARMED", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_DISARMED], 0},
|
||||||
{"PIT ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PITCH_ANGLE], 0},
|
{"PIT ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_PITCH_ANGLE], 0},
|
||||||
{"ROL ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ROLL_ANGLE], 0},
|
{"ROL ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ROLL_ANGLE], 0},
|
||||||
{"ARMED TIME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARMED_TIME], 0},
|
|
||||||
{"HEADING", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_HEADING], 0},
|
{"HEADING", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_HEADING], 0},
|
||||||
{"VARIO", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_VARIO], 0},
|
{"VARIO", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_VARIO], 0},
|
||||||
{"BACK", OME_Back, NULL, NULL, 0},
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
@ -156,6 +110,100 @@ CMS_Menu menuOsdActiveElems = {
|
||||||
.onGlobalExit = NULL,
|
.onGlobalExit = NULL,
|
||||||
.entries = menuOsdActiveElemsEntries
|
.entries = menuOsdActiveElemsEntries
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static uint8_t osdConfig_rssi_alarm;
|
||||||
|
static uint16_t osdConfig_cap_alarm;
|
||||||
|
static uint16_t osdConfig_alt_alarm;
|
||||||
|
|
||||||
|
static long menuAlarmsOnEnter(void)
|
||||||
|
{
|
||||||
|
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
||||||
|
osdConfig_cap_alarm = osdConfig()->cap_alarm;
|
||||||
|
osdConfig_alt_alarm = osdConfig()->alt_alarm;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long menuAlarmsOnExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
osdConfigMutable()->rssi_alarm = osdConfig_rssi_alarm;
|
||||||
|
osdConfigMutable()->cap_alarm = osdConfig_cap_alarm;
|
||||||
|
osdConfigMutable()->alt_alarm = osdConfig_alt_alarm;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
OSD_Entry menuAlarmsEntries[] =
|
||||||
|
{
|
||||||
|
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0},
|
||||||
|
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0},
|
||||||
|
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0},
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu menuAlarms = {
|
||||||
|
.GUARD_text = "MENUALARMS",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = menuAlarmsOnEnter,
|
||||||
|
.onExit = menuAlarmsOnExit,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuAlarmsEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
osd_timer_source_e timerSource[OSD_TIMER_COUNT];
|
||||||
|
osd_timer_precision_e timerPrecision[OSD_TIMER_COUNT];
|
||||||
|
uint8_t timerAlarm[OSD_TIMER_COUNT];
|
||||||
|
|
||||||
|
static long menuTimersOnEnter(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
||||||
|
const uint16_t timer = osdConfig()->timers[i];
|
||||||
|
timerSource[i] = OSD_TIMER_SRC(timer);
|
||||||
|
timerPrecision[i] = OSD_TIMER_PRECISION(timer);
|
||||||
|
timerAlarm[i] = OSD_TIMER_ALARM(timer);
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long menuTimersOnExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
||||||
|
osdConfigMutable()->timers[i] = OSD_TIMER(timerSource[i], timerPrecision[i], timerAlarm[i]);
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const char * osdTimerPrecisionNames[] = {"SCND", "HDTH"};
|
||||||
|
|
||||||
|
OSD_Entry menuTimersEntries[] =
|
||||||
|
{
|
||||||
|
{"--- TIMERS ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"1 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_1], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames}, 0 },
|
||||||
|
{"1 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_1], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}, 0},
|
||||||
|
{"1 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_1], 0, 0xFF, 1}, 0},
|
||||||
|
{"2 SRC", OME_TAB, NULL, &(OSD_TAB_t){&timerSource[OSD_TIMER_2], OSD_TIMER_SRC_COUNT - 1, osdTimerSourceNames}, 0 },
|
||||||
|
{"2 PREC", OME_TAB, NULL, &(OSD_TAB_t){&timerPrecision[OSD_TIMER_2], OSD_TIMER_PREC_COUNT - 1, osdTimerPrecisionNames}, 0},
|
||||||
|
{"2 ALARM", OME_UINT8, NULL, &(OSD_UINT8_t){&timerAlarm[OSD_TIMER_2], 0, 0xFF, 1}, 0},
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu menuTimers = {
|
||||||
|
.GUARD_text = "MENUTIMERS",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = menuTimersOnEnter,
|
||||||
|
.onExit = menuTimersOnExit,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuTimersEntries,
|
||||||
|
};
|
||||||
#endif /* DISABLE_EXTENDED_CMS_OSD_MENU */
|
#endif /* DISABLE_EXTENDED_CMS_OSD_MENU */
|
||||||
|
|
||||||
#ifdef USE_MAX7456
|
#ifdef USE_MAX7456
|
||||||
|
@ -193,6 +241,8 @@ OSD_Entry cmsx_menuOsdEntries[] =
|
||||||
{"---OSD---", OME_Label, NULL, NULL, 0},
|
{"---OSD---", OME_Label, NULL, NULL, 0},
|
||||||
#ifndef DISABLE_EXTENDED_CMS_OSD_MENU
|
#ifndef DISABLE_EXTENDED_CMS_OSD_MENU
|
||||||
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems, 0},
|
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems, 0},
|
||||||
|
{"TIMERS", OME_Submenu, cmsMenuChange, &menuTimers, 0},
|
||||||
|
{"ALARMS", OME_Submenu, cmsMenuChange, &menuAlarms, 0},
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_MAX7456
|
#ifdef USE_MAX7456
|
||||||
{"INVERT", OME_Bool, NULL, &displayPortProfileMax7456_invert, 0},
|
{"INVERT", OME_Bool, NULL, &displayPortProfileMax7456_invert, 0},
|
||||||
|
|
|
@ -17,5 +17,4 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
extern CMS_Menu cmsx_menuAlarms;
|
|
||||||
extern CMS_Menu cmsx_menuOsd;
|
extern CMS_Menu cmsx_menuOsd;
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/bus_i2c.h"
|
#include "drivers/bus_i2c.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
|
@ -217,6 +218,23 @@ bool mpuGyroRead(gyroDev_t *gyro)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool mpuGyroReadSPI(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
static const uint8_t dataToSend[7] = {MPU_RA_GYRO_XOUT_H | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF};
|
||||||
|
uint8_t data[7];
|
||||||
|
|
||||||
|
const bool ack = spiBusTransfer(&gyro->bus, data, dataToSend, 7);
|
||||||
|
if (!ack) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
gyro->gyroADCRaw[X] = (int16_t)((data[1] << 8) | data[2]);
|
||||||
|
gyro->gyroADCRaw[Y] = (int16_t)((data[3] << 8) | data[4]);
|
||||||
|
gyro->gyroADCRaw[Z] = (int16_t)((data[5] << 8) | data[6]);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
bool mpuCheckDataReady(gyroDev_t* gyro)
|
bool mpuCheckDataReady(gyroDev_t* gyro)
|
||||||
{
|
{
|
||||||
bool ret;
|
bool ret;
|
||||||
|
|
|
@ -199,6 +199,7 @@ void mpuGyroInit(struct gyroDev_s *gyro);
|
||||||
struct accDev_s;
|
struct accDev_s;
|
||||||
bool mpuAccRead(struct accDev_s *acc);
|
bool mpuAccRead(struct accDev_s *acc);
|
||||||
bool mpuGyroRead(struct gyroDev_s *gyro);
|
bool mpuGyroRead(struct gyroDev_s *gyro);
|
||||||
|
bool mpuGyroReadSPI(struct gyroDev_s *gyro);
|
||||||
void mpuDetect(struct gyroDev_s *gyro);
|
void mpuDetect(struct gyroDev_s *gyro);
|
||||||
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
||||||
void mpuGyroSetIsrUpdate(struct gyroDev_s *gyro, sensorGyroUpdateFuncPtr updateFn);
|
void mpuGyroSetIsrUpdate(struct gyroDev_s *gyro, sensorGyroUpdateFuncPtr updateFn);
|
||||||
|
|
|
@ -351,7 +351,7 @@ bool bmi160GyroRead(gyroDev_t *gyro)
|
||||||
};
|
};
|
||||||
|
|
||||||
uint8_t bmi160_rec_buf[BUFFER_SIZE];
|
uint8_t bmi160_rec_buf[BUFFER_SIZE];
|
||||||
uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0};
|
static const uint8_t bmi160_tx_buf[BUFFER_SIZE] = {BMI160_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0};
|
||||||
|
|
||||||
IOLo(gyro->bus.spi.csnPin);
|
IOLo(gyro->bus.spi.csnPin);
|
||||||
spiTransfer(gyro->bus.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response
|
spiTransfer(gyro->bus.spi.instance, bmi160_rec_buf, bmi160_tx_buf, BUFFER_SIZE); // receive response
|
||||||
|
|
|
@ -140,7 +140,7 @@ bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
||||||
}
|
}
|
||||||
|
|
||||||
gyro->initFn = icm20689GyroInit;
|
gyro->initFn = icm20689GyroInit;
|
||||||
gyro->readFn = mpuGyroRead;
|
gyro->readFn = mpuGyroReadSPI;
|
||||||
gyro->intStatusFn = mpuCheckDataReady;
|
gyro->intStatusFn = mpuCheckDataReady;
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
|
|
|
@ -244,7 +244,7 @@ bool mpu6000SpiGyroDetect(gyroDev_t *gyro)
|
||||||
}
|
}
|
||||||
|
|
||||||
gyro->initFn = mpu6000SpiGyroInit;
|
gyro->initFn = mpu6000SpiGyroInit;
|
||||||
gyro->readFn = mpuGyroRead;
|
gyro->readFn = mpuGyroReadSPI;
|
||||||
gyro->intStatusFn = mpuCheckDataReady;
|
gyro->intStatusFn = mpuCheckDataReady;
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
gyro->scale = 1.0f / 16.4f;
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
|
@ -136,7 +136,7 @@ bool mpu6500SpiGyroDetect(gyroDev_t *gyro)
|
||||||
}
|
}
|
||||||
|
|
||||||
gyro->initFn = mpu6500SpiGyroInit;
|
gyro->initFn = mpu6500SpiGyroInit;
|
||||||
gyro->readFn = mpuGyroRead;
|
gyro->readFn = mpuGyroReadSPI;
|
||||||
gyro->intStatusFn = mpuCheckDataReady;
|
gyro->intStatusFn = mpuCheckDataReady;
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
|
|
|
@ -210,7 +210,7 @@ bool mpu9250SpiGyroDetect(gyroDev_t *gyro)
|
||||||
}
|
}
|
||||||
|
|
||||||
gyro->initFn = mpu9250SpiGyroInit;
|
gyro->initFn = mpu9250SpiGyroInit;
|
||||||
gyro->readFn = mpuGyroRead;
|
gyro->readFn = mpuGyroReadSPI;
|
||||||
gyro->intStatusFn = mpuCheckDataReady;
|
gyro->intStatusFn = mpuCheckDataReady;
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
|
|
|
@ -51,7 +51,7 @@ SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||||
|
|
||||||
#ifdef USE_SPI_DEVICE_4
|
#ifdef USE_SPI_DEVICE_4
|
||||||
if (instance == SPI4)
|
if (instance == SPI4)
|
||||||
return SPIDEV_3;
|
return SPIDEV_4;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return SPIINVALID;
|
return SPIINVALID;
|
||||||
|
@ -240,6 +240,14 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length)
|
||||||
|
{
|
||||||
|
IOLo(bus->spi.csnPin);
|
||||||
|
spiTransfer(bus->spi.instance, rxData, txData, length);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||||
{
|
{
|
||||||
#define BR_CLEAR_MASK 0xFFC7
|
#define BR_CLEAR_MASK 0xFFC7
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/bus.h"
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
#include "drivers/bus.h"
|
#include "drivers/bus.h"
|
||||||
#include "drivers/rcc_types.h"
|
#include "drivers/rcc_types.h"
|
||||||
|
@ -93,6 +94,8 @@ uint16_t spiGetErrorCounter(SPI_TypeDef *instance);
|
||||||
void spiResetErrorCounter(SPI_TypeDef *instance);
|
void spiResetErrorCounter(SPI_TypeDef *instance);
|
||||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance);
|
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance);
|
||||||
|
|
||||||
|
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int length);
|
||||||
|
|
||||||
#if defined(USE_HAL_DRIVER)
|
#if defined(USE_HAL_DRIVER)
|
||||||
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance);
|
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance);
|
||||||
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size);
|
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size);
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
|
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
|
|
||||||
|
#include "drivers/bus.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/bus_spi_impl.h"
|
#include "drivers/bus_spi_impl.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
@ -275,7 +276,7 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
||||||
}
|
}
|
||||||
else // Tx and Rx
|
else // Tx and Rx
|
||||||
{
|
{
|
||||||
status = HAL_SPI_TransmitReceive(&spiDevice[device].hspi, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_TransmitReceive(&spiDevice[device].hspi, in, out, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ( status != HAL_OK)
|
if ( status != HAL_OK)
|
||||||
|
@ -310,6 +311,17 @@ static uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t in)
|
||||||
return in;
|
return in;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool spiBusTransfer(const busDevice_t *bus, uint8_t *rxData, const uint8_t *txData, int len)
|
||||||
|
{
|
||||||
|
IOLo(bus->spi.csnPin);
|
||||||
|
const HAL_StatusTypeDef status = HAL_SPI_TransmitReceive(bus->spi.handle, txData, rxData, len, SPI_DEFAULT_TIMEOUT);
|
||||||
|
IOHi(bus->spi.csnPin);
|
||||||
|
if (status != HAL_OK) {
|
||||||
|
spiTimeoutUserCallback(bus->spi.instance);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||||
{
|
{
|
||||||
SPIDevice device = spiDeviceByInstance(instance);
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
|
|
|
@ -61,7 +61,8 @@
|
||||||
#define AK8963_MAG_REG_HZL 0x07
|
#define AK8963_MAG_REG_HZL 0x07
|
||||||
#define AK8963_MAG_REG_HZH 0x08
|
#define AK8963_MAG_REG_HZH 0x08
|
||||||
#define AK8963_MAG_REG_STATUS2 0x09
|
#define AK8963_MAG_REG_STATUS2 0x09
|
||||||
#define AK8963_MAG_REG_CNTL 0x0a
|
#define AK8963_MAG_REG_CNTL1 0x0a
|
||||||
|
#define AK8963_MAG_REG_CNTL2 0x0b
|
||||||
#define AK8963_MAG_REG_ASCT 0x0c // self test
|
#define AK8963_MAG_REG_ASCT 0x0c // self test
|
||||||
#define AK8963_MAG_REG_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
|
#define AK8963_MAG_REG_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
|
||||||
#define AK8963_MAG_REG_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
|
#define AK8963_MAG_REG_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
|
||||||
|
@ -75,37 +76,26 @@
|
||||||
#define STATUS2_DATA_ERROR 0x02
|
#define STATUS2_DATA_ERROR 0x02
|
||||||
#define STATUS2_MAG_SENSOR_OVERFLOW 0x03
|
#define STATUS2_MAG_SENSOR_OVERFLOW 0x03
|
||||||
|
|
||||||
#define CNTL_MODE_POWER_DOWN 0x00
|
#define CNTL1_MODE_POWER_DOWN 0x00
|
||||||
#define CNTL_MODE_ONCE 0x01
|
#define CNTL1_MODE_ONCE 0x01
|
||||||
#define CNTL_MODE_CONT1 0x02
|
#define CNTL1_MODE_CONT1 0x02
|
||||||
#define CNTL_MODE_CONT2 0x06
|
#define CNTL1_MODE_CONT2 0x06
|
||||||
#define CNTL_MODE_SELF_TEST 0x08
|
#define CNTL1_MODE_SELF_TEST 0x08
|
||||||
#define CNTL_MODE_FUSE_ROM 0x0F
|
#define CNTL1_MODE_FUSE_ROM 0x0F
|
||||||
|
|
||||||
|
#define CNTL2_SOFT_RESET 0x01
|
||||||
|
|
||||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||||
|
|
||||||
#if defined(USE_SPI)
|
#if defined(MPU6500_SPI_INSTANCE) || defined(MPU9250_SPI_INSTANCE)
|
||||||
static busDevice_t *bus = NULL; // HACK
|
static busDevice_t *bus = NULL;
|
||||||
#endif
|
|
||||||
|
|
||||||
// FIXME pretend we have real MPU9250 support
|
static bool spiWriteRegisterDelay(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
||||||
// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same.
|
|
||||||
#if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
|
|
||||||
#define MPU9250_SPI_INSTANCE
|
|
||||||
#define mpu9250SpiWriteRegisterVerify mpu6500SpiWriteRegDelayed
|
|
||||||
static bool mpu6500SpiWriteRegDelayed(const busDevice_t *bus, uint8_t reg, uint8_t data)
|
|
||||||
{
|
{
|
||||||
IOLo(bus->spi.csnPin);
|
spiWriteRegister(bus, reg, data);
|
||||||
spiTransferByte(bus->spi.instance, reg);
|
|
||||||
spiTransferByte(bus->spi.instance, data);
|
|
||||||
IOHi(bus->spi.csnPin);
|
|
||||||
delayMicroseconds(10);
|
delayMicroseconds(10);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
|
||||||
|
|
||||||
typedef struct queuedReadState_s {
|
typedef struct queuedReadState_s {
|
||||||
bool waiting;
|
bool waiting;
|
||||||
|
@ -123,10 +113,10 @@ static queuedReadState_t queuedRead = { false, 0, 0};
|
||||||
|
|
||||||
static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
||||||
{
|
{
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||||
delay(10);
|
delay(4);
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
bool ack = spiReadRegisterBuffer(bus, MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
bool ack = spiReadRegisterBuffer(bus, MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
||||||
__enable_irq();
|
__enable_irq();
|
||||||
|
@ -135,10 +125,10 @@ static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t
|
||||||
|
|
||||||
static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||||
{
|
{
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -150,9 +140,9 @@ static bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
||||||
|
|
||||||
queuedRead.len = len_;
|
queuedRead.len = len_;
|
||||||
|
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
mpu9250SpiWriteRegisterVerify(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
spiWriteRegisterDelay(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||||
|
|
||||||
queuedRead.readStartedAt = micros();
|
queuedRead.readStartedAt = micros();
|
||||||
queuedRead.waiting = true;
|
queuedRead.waiting = true;
|
||||||
|
@ -207,32 +197,22 @@ static bool ak8963Init()
|
||||||
uint8_t calibration[3];
|
uint8_t calibration[3];
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
|
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down before entering fuse mode
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL1, CNTL1_MODE_POWER_DOWN); // power down before entering fuse mode
|
||||||
delay(20);
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL1, CNTL1_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
||||||
|
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_FUSE_ROM); // Enter Fuse ROM access mode
|
|
||||||
delay(10);
|
|
||||||
|
|
||||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_ASAX, sizeof(calibration), calibration); // Read the x-, y-, and z-axis calibration values
|
||||||
delay(10);
|
|
||||||
|
|
||||||
magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30);
|
magGain[X] = (((((float)(int8_t)calibration[X] - 128) / 256) + 1) * 30);
|
||||||
magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30);
|
magGain[Y] = (((((float)(int8_t)calibration[Y] - 128) / 256) + 1) * 30);
|
||||||
magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30);
|
magGain[Z] = (((((float)(int8_t)calibration[Z] - 128) / 256) + 1) * 30);
|
||||||
|
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_POWER_DOWN); // power down after reading.
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL1, CNTL1_MODE_POWER_DOWN); // power down after reading.
|
||||||
delay(10);
|
|
||||||
|
|
||||||
// Clear status registers
|
// Clear status registers
|
||||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS1, 1, &status);
|
||||||
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||||
|
|
||||||
// Trigger first measurement
|
// Trigger first measurement
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL1, CNTL1_MODE_ONCE);
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
|
||||||
#else
|
|
||||||
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
|
||||||
#endif
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -241,7 +221,7 @@ static bool ak8963Read(int16_t *magData)
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t buf[7];
|
uint8_t buf[7];
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(MPU6500_SPI_INSTANCE) || defined(MPU9250_SPI_INSTANCE)
|
||||||
|
|
||||||
// we currently need a different approach for the MPU9250 connected via SPI.
|
// we currently need a different approach for the MPU9250 connected via SPI.
|
||||||
// we cannot use the ak8963SensorRead() method for SPI, it is to slow and blocks for far too long.
|
// we cannot use the ak8963SensorRead() method for SPI, it is to slow and blocks for far too long.
|
||||||
|
@ -267,7 +247,7 @@ restart:
|
||||||
|
|
||||||
uint8_t status = buf[0];
|
uint8_t status = buf[0];
|
||||||
|
|
||||||
if (!ack || ((status & STATUS1_DATA_READY) == 0 && (status & STATUS1_DATA_OVERRUN) == 0)) {
|
if (!ack || (status & STATUS1_DATA_READY) == 0) {
|
||||||
// too early. queue the status read again
|
// too early. queue the status read again
|
||||||
state = CHECK_STATUS;
|
state = CHECK_STATUS;
|
||||||
if (retry) {
|
if (retry) {
|
||||||
|
@ -315,37 +295,34 @@ restart:
|
||||||
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
magData[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
||||||
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(MPU6500_SPI_INSTANCE) || defined(MPU9250_SPI_INSTANCE)
|
||||||
state = CHECK_STATUS;
|
state = CHECK_STATUS;
|
||||||
return true;
|
|
||||||
#else
|
|
||||||
return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again
|
|
||||||
#endif
|
#endif
|
||||||
|
return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL1, CNTL1_MODE_ONCE); // start reading again
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ak8963Detect(magDev_t *mag)
|
bool ak8963Detect(magDev_t *mag)
|
||||||
{
|
{
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
|
||||||
#if defined(USE_SPI)
|
#if defined(MPU6500_SPI_INSTANCE) || defined(MPU9250_SPI_INSTANCE)
|
||||||
bus = &mag->bus;
|
bus = &mag->bus;
|
||||||
#if defined(MPU6500_SPI_INSTANCE)
|
#if defined(MPU6500_SPI_INSTANCE)
|
||||||
spiBusSetInstance(&mag->bus, MPU6500_SPI_INSTANCE);
|
spiBusSetInstance(&mag->bus, MPU6500_SPI_INSTANCE);
|
||||||
#elif defined(MPU9250_SPI_INSTANCE)
|
#elif defined(MPU9250_SPI_INSTANCE)
|
||||||
spiBusSetInstance(&mag->bus, MPU9250_SPI_INSTANCE);
|
spiBusSetInstance(&mag->bus, MPU9250_SPI_INSTANCE);
|
||||||
|
#endif
|
||||||
|
|
||||||
// initialze I2C master via SPI bus (MPU9250)
|
// initialze I2C master via SPI bus (MPU9250)
|
||||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN);
|
spiWriteRegisterDelay(&mag->bus, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN);
|
||||||
delay(10);
|
spiWriteRegisterDelay(&mag->bus, MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
spiWriteRegisterDelay(&mag->bus, MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||||
delay(10);
|
|
||||||
mpu9250SpiWriteRegisterVerify(&mag->bus, MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
|
||||||
delay(10);
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// check for AK8963
|
ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL2, CNTL2_SOFT_RESET); // reset MAG
|
||||||
bool ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
|
delay(4);
|
||||||
|
|
||||||
|
bool ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); // check for AK8963
|
||||||
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
|
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
|
||||||
{
|
{
|
||||||
mag->init = ak8963Init;
|
mag->init = ak8963Init;
|
||||||
|
|
|
@ -29,17 +29,23 @@ PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONF
|
||||||
static IO_t leds[STATUS_LED_NUMBER];
|
static IO_t leds[STATUS_LED_NUMBER];
|
||||||
static uint8_t ledInversion = 0;
|
static uint8_t ledInversion = 0;
|
||||||
|
|
||||||
|
#ifndef LED0_PIN
|
||||||
|
#define LED0_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LED1_PIN
|
||||||
|
#define LED1_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LED2_PIN
|
||||||
|
#define LED2_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
|
||||||
{
|
{
|
||||||
#ifdef LED0_PIN
|
|
||||||
statusLedConfig->ioTags[0] = IO_TAG(LED0_PIN);
|
statusLedConfig->ioTags[0] = IO_TAG(LED0_PIN);
|
||||||
#endif
|
|
||||||
#ifdef LED1_PIN
|
|
||||||
statusLedConfig->ioTags[1] = IO_TAG(LED1_PIN);
|
statusLedConfig->ioTags[1] = IO_TAG(LED1_PIN);
|
||||||
#endif
|
|
||||||
#ifdef LED2_PIN
|
|
||||||
statusLedConfig->ioTags[2] = IO_TAG(LED2_PIN);
|
statusLedConfig->ioTags[2] = IO_TAG(LED2_PIN);
|
||||||
#endif
|
|
||||||
|
|
||||||
statusLedConfig->inversion = 0
|
statusLedConfig->inversion = 0
|
||||||
#ifdef LED0_INVERTED
|
#ifdef LED0_INVERTED
|
||||||
|
|
|
@ -45,8 +45,8 @@ static pwmOutputPort_t beeperPwm;
|
||||||
static uint16_t freqBeep = 0;
|
static uint16_t freqBeep = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
bool pwmMotorsEnabled = false;
|
static bool pwmMotorsEnabled = false;
|
||||||
bool isDshot = false;
|
static bool isDshot = false;
|
||||||
|
|
||||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
{
|
{
|
||||||
|
@ -169,10 +169,8 @@ static uint8_t loadDmaBufferProshot(motorDmaOutput_t *const motor, uint16_t pack
|
||||||
|
|
||||||
void pwmWriteMotor(uint8_t index, float value)
|
void pwmWriteMotor(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
if (pwmMotorsEnabled) {
|
|
||||||
pwmWrite(index, value);
|
pwmWrite(index, value);
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
|
@ -397,8 +395,7 @@ void pwmWriteDshotCommand(uint8_t index, uint8_t command)
|
||||||
for (; repeats; repeats--) {
|
for (; repeats; repeats--) {
|
||||||
motor->requestTelemetry = true;
|
motor->requestTelemetry = true;
|
||||||
pwmWriteDshotInt(index, command);
|
pwmWriteDshotInt(index, command);
|
||||||
pwmCompleteMotorUpdate(0);
|
pwmCompleteDshotMotorUpdate(0);
|
||||||
|
|
||||||
delay(1);
|
delay(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -125,8 +125,6 @@ typedef struct {
|
||||||
|
|
||||||
motorDmaOutput_t *getMotorDmaOutput(uint8_t index);
|
motorDmaOutput_t *getMotorDmaOutput(uint8_t index);
|
||||||
|
|
||||||
extern bool pwmMotorsEnabled;
|
|
||||||
|
|
||||||
struct timerHardware_s;
|
struct timerHardware_s;
|
||||||
typedef void pwmWriteFunc(uint8_t index, float value); // function pointer used to write motors
|
typedef void pwmWriteFunc(uint8_t index, float value); // function pointer used to write motors
|
||||||
typedef void pwmCompleteWriteFunc(uint8_t motorCount); // function pointer used after motors are written
|
typedef void pwmCompleteWriteFunc(uint8_t motorCount); // function pointer used after motors are written
|
||||||
|
@ -134,11 +132,11 @@ typedef void pwmCompleteWriteFunc(uint8_t motorCount); // function pointer use
|
||||||
typedef struct {
|
typedef struct {
|
||||||
volatile timCCR_t *ccr;
|
volatile timCCR_t *ccr;
|
||||||
TIM_TypeDef *tim;
|
TIM_TypeDef *tim;
|
||||||
|
float pulseScale;
|
||||||
|
float pulseOffset;
|
||||||
bool forceOverflow;
|
bool forceOverflow;
|
||||||
bool enabled;
|
bool enabled;
|
||||||
IO_t io;
|
IO_t io;
|
||||||
float pulseScale;
|
|
||||||
float pulseOffset;
|
|
||||||
} pwmOutputPort_t;
|
} pwmOutputPort_t;
|
||||||
|
|
||||||
typedef struct motorDevConfig_s {
|
typedef struct motorDevConfig_s {
|
||||||
|
|
|
@ -74,10 +74,6 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
UNUSED(motorCount);
|
UNUSED(motorCount);
|
||||||
|
|
||||||
if (!pwmMotorsEnabled) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||||
|
|
|
@ -1,8 +1,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#include "sdcard_standard.h"
|
#include "sdcard_standard.h"
|
||||||
|
#include "common/maths.h"
|
||||||
#define MIN(a, b) ((a) < (b) ? (a) : (b))
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Read a bitfield from an array of bits (the bit at index 0 being the most-significant bit of the first byte in
|
* Read a bitfield from an array of bits (the bit at index 0 being the most-significant bit of the first byte in
|
||||||
|
|
|
@ -56,6 +56,9 @@ typedef enum {
|
||||||
static serialPort_t *escPort = NULL;
|
static serialPort_t *escPort = NULL;
|
||||||
static serialPort_t *passPort = NULL;
|
static serialPort_t *passPort = NULL;
|
||||||
|
|
||||||
|
#define ICPOLARITY_RISING true
|
||||||
|
#define ICPOLARITY_FALLING false
|
||||||
|
|
||||||
typedef struct escSerial_s {
|
typedef struct escSerial_s {
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
|
|
||||||
|
@ -67,6 +70,11 @@ typedef struct escSerial_s {
|
||||||
const timerHardware_t *txTimerHardware;
|
const timerHardware_t *txTimerHardware;
|
||||||
volatile uint8_t txBuffer[ESCSERIAL_BUFFER_SIZE];
|
volatile uint8_t txBuffer[ESCSERIAL_BUFFER_SIZE];
|
||||||
|
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
const TIM_HandleTypeDef *txTimerHandle;
|
||||||
|
const TIM_HandleTypeDef *rxTimerHandle;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t isSearchingForStartBit;
|
uint8_t isSearchingForStartBit;
|
||||||
uint8_t rxBitIndex;
|
uint8_t rxBitIndex;
|
||||||
uint8_t rxLastLeadingEdgeAtBitIndex;
|
uint8_t rxLastLeadingEdgeAtBitIndex;
|
||||||
|
@ -119,7 +127,14 @@ void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
static void escSerialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
|
||||||
|
// XXX No TIM_DeInit equivalent in HAL driver???
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
static void TIM_DeInit(TIM_TypeDef *tim)
|
||||||
|
{
|
||||||
|
UNUSED(tim);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
||||||
{
|
{
|
||||||
|
@ -152,22 +167,28 @@ void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg)
|
static void escSerialGPIOConfig(const timerHardware_t *timhw, ioConfig_t cfg)
|
||||||
{
|
{
|
||||||
|
ioTag_t tag = timhw->tag;
|
||||||
|
|
||||||
if (!tag) {
|
if (!tag) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
IOInit(IOGetByTag(tag), OWNER_MOTOR, 0);
|
IOInit(IOGetByTag(tag), OWNER_MOTOR, 0);
|
||||||
|
#ifdef STM32F7
|
||||||
|
IOConfigGPIOAF(IOGetByTag(tag), cfg, timhw->alternateFunction);
|
||||||
|
#else
|
||||||
IOConfigGPIO(IOGetByTag(tag), cfg);
|
IOConfigGPIO(IOGetByTag(tag), cfg);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void escSerialInputPortConfig(const timerHardware_t *timerHardwarePtr)
|
void escSerialInputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
#ifdef STM32F10X
|
#ifdef STM32F10X
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU);
|
escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU);
|
||||||
#else
|
#else
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_AF_PP_UP);
|
escSerialGPIOConfig(timerHardwarePtr, IOCFG_AF_PP_UP);
|
||||||
#endif
|
#endif
|
||||||
timerChClearCCFlag(timerHardwarePtr);
|
timerChClearCCFlag(timerHardwarePtr);
|
||||||
timerChITConfig(timerHardwarePtr,ENABLE);
|
timerChITConfig(timerHardwarePtr,ENABLE);
|
||||||
|
@ -206,7 +227,7 @@ static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
||||||
// start bit is usually a FALLING signal
|
// start bit is usually a FALLING signal
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, SystemCoreClock / 2);
|
timerConfigure(timerHardwarePtr, 0xFFFF, SystemCoreClock / 2);
|
||||||
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
timerChConfigIC(timerHardwarePtr, (options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
}
|
}
|
||||||
|
@ -220,33 +241,19 @@ static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void escSerialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
|
||||||
{
|
|
||||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
|
||||||
|
|
||||||
TIM_ICStructInit(&TIM_ICInitStructure);
|
|
||||||
TIM_ICInitStructure.TIM_Channel = channel;
|
|
||||||
TIM_ICInitStructure.TIM_ICPolarity = polarity;
|
|
||||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
|
||||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
|
||||||
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
|
||||||
|
|
||||||
TIM_ICInit(tim, &TIM_ICInitStructure);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||||
{
|
{
|
||||||
// start bit is usually a FALLING signal
|
// start bit is usually a FALLING signal
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, MHZ_TO_HZ(1));
|
timerConfigure(timerHardwarePtr, 0xFFFF, MHZ_TO_HZ(1));
|
||||||
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
timerChConfigIC(timerHardwarePtr, ICPOLARITY_FALLING, 0);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void escSerialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
static void escSerialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_OUT_PP);
|
escSerialGPIOConfig(timerHardwarePtr, IOCFG_OUT_PP);
|
||||||
timerChITConfig(timerHardwarePtr,DISABLE);
|
timerChITConfig(timerHardwarePtr,DISABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -269,6 +276,9 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac
|
||||||
|
|
||||||
if (mode != PROTOCOL_KISSALL) {
|
if (mode != PROTOCOL_KISSALL) {
|
||||||
escSerial->rxTimerHardware = &(timerHardware[output]);
|
escSerial->rxTimerHardware = &(timerHardware[output]);
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
escSerial->rxTimerHandle = timerFindTimerHandle(escSerial->rxTimerHardware->tim);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
escSerial->mode = mode;
|
escSerial->mode = mode;
|
||||||
|
@ -278,6 +288,10 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
escSerial->txTimerHandle = timerFindTimerHandle(escSerial->txTimerHardware->tim);
|
||||||
|
#endif
|
||||||
|
|
||||||
escSerial->port.vTable = escSerialVTable;
|
escSerial->port.vTable = escSerialVTable;
|
||||||
escSerial->port.baudRate = baud;
|
escSerial->port.baudRate = baud;
|
||||||
escSerial->port.mode = MODE_RXTX;
|
escSerial->port.mode = MODE_RXTX;
|
||||||
|
@ -355,7 +369,7 @@ void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
timerChClearCCFlag(timerHardwarePtr);
|
timerChClearCCFlag(timerHardwarePtr);
|
||||||
timerChITConfig(timerHardwarePtr,DISABLE);
|
timerChITConfig(timerHardwarePtr,DISABLE);
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU);
|
escSerialGPIOConfig(timerHardwarePtr, IOCFG_IPU);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -547,10 +561,9 @@ void prepareForNextRxByteBL(escSerial_t *escSerial)
|
||||||
escSerial->isSearchingForStartBit = true;
|
escSerial->isSearchingForStartBit = true;
|
||||||
if (escSerial->rxEdge == LEADING) {
|
if (escSerial->rxEdge == LEADING) {
|
||||||
escSerial->rxEdge = TRAILING;
|
escSerial->rxEdge = TRAILING;
|
||||||
escSerialICConfig(
|
timerChConfigIC(
|
||||||
escSerial->rxTimerHardware->tim,
|
escSerial->rxTimerHardware,
|
||||||
escSerial->rxTimerHardware->channel,
|
(escSerial->port.options & SERIAL_INVERTED) ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0
|
||||||
(escSerial->port.options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling
|
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -627,15 +640,19 @@ void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (escSerial->isSearchingForStartBit) {
|
if (escSerial->isSearchingForStartBit) {
|
||||||
// synchronise bit counter
|
// Adjust the timing so it will interrupt on the middle.
|
||||||
// FIXME this reduces functionality somewhat as receiving breaks concurrent transmission on all ports because
|
// This is clobbers transmission, but it is okay because we are
|
||||||
// the next callback to the onSerialTimer will happen too early causing transmission errors.
|
// always half-duplex.
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
__HAL_TIM_SetCounter(escSerial->txTimerHandle, __HAL_TIM_GetAutoreload(escSerial->txTimerHandle) / 2);
|
||||||
|
#else
|
||||||
TIM_SetCounter(escSerial->txTimerHardware->tim, escSerial->txTimerHardware->tim->ARR / 2);
|
TIM_SetCounter(escSerial->txTimerHardware->tim, escSerial->txTimerHardware->tim->ARR / 2);
|
||||||
|
#endif
|
||||||
if (escSerial->isTransmittingData) {
|
if (escSerial->isTransmittingData) {
|
||||||
escSerial->transmissionErrors++;
|
escSerial->transmissionErrors++;
|
||||||
}
|
}
|
||||||
|
|
||||||
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
timerChConfigIC(escSerial->rxTimerHardware, inverted ? ICPOLARITY_FALLING : ICPOLARITY_RISING, 0);
|
||||||
escSerial->rxEdge = LEADING;
|
escSerial->rxEdge = LEADING;
|
||||||
|
|
||||||
escSerial->rxBitIndex = 0;
|
escSerial->rxBitIndex = 0;
|
||||||
|
@ -653,10 +670,10 @@ void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
|
|
||||||
if (escSerial->rxEdge == TRAILING) {
|
if (escSerial->rxEdge == TRAILING) {
|
||||||
escSerial->rxEdge = LEADING;
|
escSerial->rxEdge = LEADING;
|
||||||
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
timerChConfigIC(escSerial->rxTimerHardware, inverted ? ICPOLARITY_FALLING : ICPOLARITY_RISING, 0);
|
||||||
} else {
|
} else {
|
||||||
escSerial->rxEdge = TRAILING;
|
escSerial->rxEdge = TRAILING;
|
||||||
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
timerChConfigIC(escSerial->rxTimerHardware, inverted ? ICPOLARITY_RISING : ICPOLARITY_FALLING, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*-------------------------BL*/
|
/*-------------------------BL*/
|
||||||
|
@ -689,7 +706,7 @@ void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
{
|
{
|
||||||
escSerial->isReceivingData=0;
|
escSerial->isReceivingData=0;
|
||||||
escSerial->receiveTimeout=0;
|
escSerial->receiveTimeout=0;
|
||||||
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Falling);
|
timerChConfigIC(escSerial->rxTimerHardware, ICPOLARITY_FALLING, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -707,7 +724,11 @@ void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
||||||
escSerial_t *escSerial = container_of(cbRec, escSerial_t, edgeCb);
|
escSerial_t *escSerial = container_of(cbRec, escSerial_t, edgeCb);
|
||||||
|
|
||||||
//clear timer
|
//clear timer
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
__HAL_TIM_SetCounter(escSerial->rxTimerHandle, 0);
|
||||||
|
#else
|
||||||
TIM_SetCounter(escSerial->rxTimerHardware->tim,0);
|
TIM_SetCounter(escSerial->rxTimerHardware->tim,0);
|
||||||
|
#endif
|
||||||
|
|
||||||
if (capture > 40 && capture < 90)
|
if (capture > 40 && capture < 90)
|
||||||
{
|
{
|
||||||
|
@ -739,7 +760,7 @@ void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
||||||
bits=1;
|
bits=1;
|
||||||
escSerial->internalRxBuffer = 0x80;
|
escSerial->internalRxBuffer = 0x80;
|
||||||
|
|
||||||
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Rising);
|
timerChConfigIC(escSerial->rxTimerHardware, ICPOLARITY_RISING, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
escSerial->receiveTimeout = 0;
|
escSerial->receiveTimeout = 0;
|
||||||
|
@ -849,7 +870,7 @@ void escSerialInitialize()
|
||||||
// set outputs to pullup
|
// set outputs to pullup
|
||||||
if (timerHardware[i].output & TIMER_OUTPUT_ENABLED)
|
if (timerHardware[i].output & TIMER_OUTPUT_ENABLED)
|
||||||
{
|
{
|
||||||
escSerialGPIOConfig(timerHardware[i].tag, IOCFG_IPU); //GPIO_Mode_IPU
|
escSerialGPIOConfig(&timerHardware[i], IOCFG_IPU); //GPIO_Mode_IPU
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -262,8 +262,6 @@ PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONF
|
||||||
|
|
||||||
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
||||||
{
|
{
|
||||||
memset(serialPinConfig, 0, sizeof(*serialPinConfig));
|
|
||||||
|
|
||||||
for (size_t index = 0 ; index < ARRAYLEN(serialDefaultPin) ; index++) {
|
for (size_t index = 0 ; index < ARRAYLEN(serialDefaultPin) ; index++) {
|
||||||
const serialDefaultPin_t *defpin = &serialDefaultPin[index];
|
const serialDefaultPin_t *defpin = &serialDefaultPin[index];
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
|
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
|
||||||
|
|
|
@ -43,7 +43,7 @@ void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
||||||
{
|
{
|
||||||
uartDevice_t *uartdev = uartDevice;
|
uartDevice_t *uartdev = uartDevice;
|
||||||
|
|
||||||
for (size_t hindex = 0; hindex < UARTDEV_COUNT_MAX; hindex++) {
|
for (size_t hindex = 0; hindex < UARTDEV_COUNT; hindex++) {
|
||||||
|
|
||||||
const uartHardware_t *hardware = &uartHardware[hindex];
|
const uartHardware_t *hardware = &uartHardware[hindex];
|
||||||
UARTDevice device = hardware->device;
|
UARTDevice device = hardware->device;
|
||||||
|
|
|
@ -162,49 +162,45 @@ void delay(uint32_t ms)
|
||||||
}
|
}
|
||||||
|
|
||||||
#define SHORT_FLASH_DURATION 50
|
#define SHORT_FLASH_DURATION 50
|
||||||
|
#define SHORT_FLASH_COUNT 5
|
||||||
#define CODE_FLASH_DURATION 250
|
#define CODE_FLASH_DURATION 250
|
||||||
|
|
||||||
void failureLedCode(failureMode_e mode, int codeRepeatsRemaining)
|
static void indicate(uint8_t count, uint16_t duration)
|
||||||
{
|
{
|
||||||
int codeFlashesRemaining;
|
if (count) {
|
||||||
int shortFlashesRemaining;
|
|
||||||
|
|
||||||
while (codeRepeatsRemaining--) {
|
|
||||||
LED1_ON;
|
LED1_ON;
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
shortFlashesRemaining = 5;
|
|
||||||
codeFlashesRemaining = mode + 1;
|
|
||||||
uint8_t flashDuration = SHORT_FLASH_DURATION;
|
|
||||||
|
|
||||||
while (shortFlashesRemaining || codeFlashesRemaining) {
|
while (count--) {
|
||||||
LED1_TOGGLE;
|
LED1_TOGGLE;
|
||||||
LED0_TOGGLE;
|
LED0_TOGGLE;
|
||||||
BEEP_ON;
|
BEEP_ON;
|
||||||
delay(flashDuration);
|
delay(duration);
|
||||||
|
|
||||||
LED1_TOGGLE;
|
LED1_TOGGLE;
|
||||||
LED0_TOGGLE;
|
LED0_TOGGLE;
|
||||||
BEEP_OFF;
|
BEEP_OFF;
|
||||||
delay(flashDuration);
|
delay(duration);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void indicateFailure(failureMode_e mode, int codeRepeatsRemaining)
|
||||||
|
{
|
||||||
|
while (codeRepeatsRemaining--) {
|
||||||
|
indicate(SHORT_FLASH_COUNT, SHORT_FLASH_DURATION);
|
||||||
|
|
||||||
if (shortFlashesRemaining) {
|
|
||||||
shortFlashesRemaining--;
|
|
||||||
if (shortFlashesRemaining == 0) {
|
|
||||||
delay(500);
|
delay(500);
|
||||||
flashDuration = CODE_FLASH_DURATION;
|
|
||||||
}
|
indicate(mode + 1, CODE_FLASH_DURATION);
|
||||||
} else {
|
|
||||||
codeFlashesRemaining--;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void failureMode(failureMode_e mode)
|
void failureMode(failureMode_e mode)
|
||||||
{
|
{
|
||||||
failureLedCode(mode, 10);
|
indicateFailure(mode, 10);
|
||||||
|
|
||||||
#ifdef DEBUG
|
#ifdef DEBUG
|
||||||
systemReset();
|
systemReset();
|
||||||
|
|
|
@ -33,7 +33,7 @@ typedef enum {
|
||||||
} failureMode_e;
|
} failureMode_e;
|
||||||
|
|
||||||
// failure
|
// failure
|
||||||
void failureLedCode(failureMode_e mode, int repeatCount);
|
void indicateFailure(failureMode_e mode, int repeatCount);
|
||||||
void failureMode(failureMode_e mode);
|
void failureMode(failureMode_e mode);
|
||||||
|
|
||||||
// bootloader/IAP
|
// bootloader/IAP
|
||||||
|
|
|
@ -182,7 +182,6 @@ void timerInit(void);
|
||||||
void timerStart(void);
|
void timerStart(void);
|
||||||
void timerForceOverflow(TIM_TypeDef *tim);
|
void timerForceOverflow(TIM_TypeDef *tim);
|
||||||
|
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
|
||||||
uint32_t timerClock(TIM_TypeDef *tim);
|
uint32_t timerClock(TIM_TypeDef *tim);
|
||||||
|
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); // TODO - just for migration
|
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); // TODO - just for migration
|
||||||
|
|
|
@ -44,12 +44,6 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|
||||||
{
|
|
||||||
UNUSED(tim);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t timerClock(TIM_TypeDef *tim)
|
uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
{
|
{
|
||||||
UNUSED(tim);
|
UNUSED(tim);
|
||||||
|
|
|
@ -36,12 +36,6 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||||
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), .inputIrq = TIM1_TRG_COM_TIM17_IRQn },
|
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), .inputIrq = TIM1_TRG_COM_TIM17_IRQn },
|
||||||
};
|
};
|
||||||
|
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|
||||||
{
|
|
||||||
UNUSED(tim);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t timerClock(TIM_TypeDef *tim)
|
uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
{
|
{
|
||||||
UNUSED(tim);
|
UNUSED(tim);
|
||||||
|
|
|
@ -80,26 +80,18 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||||
7 TIM8_CH1 TIM8_CH2 TIM8_CH3 TIM8_CH4
|
7 TIM8_CH1 TIM8_CH2 TIM8_CH3 TIM8_CH4
|
||||||
*/
|
*/
|
||||||
|
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|
||||||
{
|
|
||||||
#if defined (STM32F40_41xxx)
|
|
||||||
if (tim == TIM8) return 1;
|
|
||||||
#endif
|
|
||||||
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
|
||||||
return 1;
|
|
||||||
} else {
|
|
||||||
return 2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t timerClock(TIM_TypeDef *tim)
|
uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
{
|
{
|
||||||
#if defined (STM32F40_41xxx)
|
#if defined (STM32F411xE)
|
||||||
if (tim == TIM8) return SystemCoreClock;
|
UNUSED(tim);
|
||||||
#endif
|
return SystemCoreClock;
|
||||||
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
#elif defined (STM32F40_41xxx)
|
||||||
|
if (tim == TIM8 || tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
|
||||||
return SystemCoreClock;
|
return SystemCoreClock;
|
||||||
} else {
|
} else {
|
||||||
return SystemCoreClock / 2;
|
return SystemCoreClock / 2;
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
#error "No timer clock defined correctly for MCU"
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -75,11 +75,6 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
|
||||||
6 TIM1_CH1 TIM1_CH2 TIM1_CH1 TIM1_CH4 TIM1_CH3
|
6 TIM1_CH1 TIM1_CH2 TIM1_CH1 TIM1_CH4 TIM1_CH3
|
||||||
7 TIM8_CH1 TIM8_CH2 TIM8_CH3 TIM8_CH4
|
7 TIM8_CH1 TIM8_CH2 TIM8_CH3 TIM8_CH4
|
||||||
*/
|
*/
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim)
|
|
||||||
{
|
|
||||||
UNUSED(tim);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t timerClock(TIM_TypeDef *tim)
|
uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
{
|
{
|
||||||
|
|
|
@ -190,13 +190,6 @@ static const char * const *sensorHardwareNames[] = {
|
||||||
};
|
};
|
||||||
#endif // USE_SENSOR_NAMES
|
#endif // USE_SENSOR_NAMES
|
||||||
|
|
||||||
#ifndef MINIMAL_CLI
|
|
||||||
static const char *armingDisableFlagNames[] = {
|
|
||||||
"NOGYRO", "FAILSAFE", "BOXFAILSAFE", "THROTTLE",
|
|
||||||
"ANGLE", "LOAD", "CALIB", "CLI", "CMS", "OSD", "BST"
|
|
||||||
};
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static void cliPrint(const char *str)
|
static void cliPrint(const char *str)
|
||||||
{
|
{
|
||||||
while (*str) {
|
while (*str) {
|
||||||
|
@ -2090,7 +2083,7 @@ static void printMap(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfi
|
||||||
char buf[16];
|
char buf[16];
|
||||||
char bufDefault[16];
|
char bufDefault[16];
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
|
for (i = 0; i < RX_MAPPABLE_CHANNEL_COUNT; i++) {
|
||||||
buf[rxConfig->rcmap[i]] = rcChannelLetters[i];
|
buf[rxConfig->rcmap[i]] = rcChannelLetters[i];
|
||||||
if (defaultRxConfig) {
|
if (defaultRxConfig) {
|
||||||
bufDefault[defaultRxConfig->rcmap[i]] = rcChannelLetters[i];
|
bufDefault[defaultRxConfig->rcmap[i]] = rcChannelLetters[i];
|
||||||
|
@ -2238,7 +2231,7 @@ static void cliDshotProg(char *cmdline)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
motorControlEnable = false;
|
pwmDisableMotors();
|
||||||
|
|
||||||
int command = atoi(pch);
|
int command = atoi(pch);
|
||||||
if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
|
if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
|
||||||
|
@ -2266,7 +2259,7 @@ static void cliDshotProg(char *cmdline)
|
||||||
pch = strtok_r(NULL, " ", &saveptr);
|
pch = strtok_r(NULL, " ", &saveptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
motorControlEnable = true;
|
pwmEnableMotors();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -120,6 +120,16 @@ PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
|
||||||
|
|
||||||
#ifndef USE_OSD_SLAVE
|
#ifndef USE_OSD_SLAVE
|
||||||
|
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
|
||||||
|
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
|
.pidProfileIndex = 0,
|
||||||
|
.activeRateProfile = 0,
|
||||||
|
.debug_mode = DEBUG_MODE,
|
||||||
|
.task_statistics = true,
|
||||||
|
.cpu_overclock = false,
|
||||||
|
.name = { 0 } // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
|
||||||
|
);
|
||||||
|
#else
|
||||||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
.pidProfileIndex = 0,
|
.pidProfileIndex = 0,
|
||||||
.activeRateProfile = 0,
|
.activeRateProfile = 0,
|
||||||
|
@ -128,6 +138,7 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
.name = { 0 } // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
|
.name = { 0 } // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_OSD_SLAVE
|
#ifdef USE_OSD_SLAVE
|
||||||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||||
|
|
|
@ -72,6 +72,9 @@ typedef struct systemConfig_s {
|
||||||
uint8_t activeRateProfile;
|
uint8_t activeRateProfile;
|
||||||
uint8_t debug_mode;
|
uint8_t debug_mode;
|
||||||
uint8_t task_statistics;
|
uint8_t task_statistics;
|
||||||
|
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
|
||||||
|
uint8_t cpu_overclock;
|
||||||
|
#endif
|
||||||
char name[MAX_NAME_LENGTH + 1]; // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
|
char name[MAX_NAME_LENGTH + 1]; // FIXME misplaced, see PG_PILOT_CONFIG in CF v1.x
|
||||||
} systemConfig_t;
|
} systemConfig_t;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -35,6 +36,7 @@
|
||||||
|
|
||||||
#include "drivers/gyro_sync.h"
|
#include "drivers/gyro_sync.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/transponder_ir.h"
|
#include "drivers/transponder_ir.h"
|
||||||
|
|
||||||
|
@ -106,12 +108,11 @@ int16_t magHold;
|
||||||
|
|
||||||
int16_t headFreeModeHold;
|
int16_t headFreeModeHold;
|
||||||
|
|
||||||
uint8_t motorControlEnable = false;
|
|
||||||
static bool reverseMotors = false;
|
static bool reverseMotors = false;
|
||||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||||
|
|
||||||
bool isRXDataNew;
|
bool isRXDataNew;
|
||||||
static bool armingCalibrationWasInitialised;
|
static int lastArmingDisabledReason = 0;
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0);
|
||||||
|
|
||||||
|
@ -141,6 +142,11 @@ static bool isCalibrating()
|
||||||
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete());
|
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void resetArmingDisabled(void)
|
||||||
|
{
|
||||||
|
lastArmingDisabledReason = 0;
|
||||||
|
}
|
||||||
|
|
||||||
void updateArmingStatus(void)
|
void updateArmingStatus(void)
|
||||||
{
|
{
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
|
@ -188,8 +194,6 @@ void updateArmingStatus(void)
|
||||||
|
|
||||||
void disarm(void)
|
void disarm(void)
|
||||||
{
|
{
|
||||||
armingCalibrationWasInitialised = false;
|
|
||||||
|
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
DISABLE_ARMING_FLAG(ARMED);
|
DISABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
|
@ -205,12 +209,8 @@ void disarm(void)
|
||||||
|
|
||||||
void tryArm(void)
|
void tryArm(void)
|
||||||
{
|
{
|
||||||
static bool firstArmingCalibrationWasCompleted;
|
if (armingConfig()->gyro_cal_on_first_arm) {
|
||||||
|
gyroStartCalibration(true);
|
||||||
if (armingConfig()->gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
|
|
||||||
gyroStartCalibration();
|
|
||||||
armingCalibrationWasInitialised = true;
|
|
||||||
firstArmingCalibrationWasCompleted = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
updateArmingStatus();
|
updateArmingStatus();
|
||||||
|
@ -242,6 +242,8 @@ void tryArm(void)
|
||||||
|
|
||||||
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||||
|
|
||||||
|
lastArmingDisabledReason = 0;
|
||||||
|
|
||||||
//beep to indicate arming
|
//beep to indicate arming
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
|
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
|
||||||
|
@ -252,12 +254,15 @@ void tryArm(void)
|
||||||
#else
|
#else
|
||||||
beeper(BEEPER_ARMING);
|
beeper(BEEPER_ARMING);
|
||||||
#endif
|
#endif
|
||||||
|
} else {
|
||||||
|
if (!isFirstArmingGyroCalibrationRunning()) {
|
||||||
|
int armingDisabledReason = ffs(getArmingDisableFlags());
|
||||||
|
if (lastArmingDisabledReason != armingDisabledReason) {
|
||||||
|
lastArmingDisabledReason = armingDisabledReason;
|
||||||
|
|
||||||
return;
|
beeperWarningBeeps(armingDisabledReason);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED)) {
|
|
||||||
beeperConfirmationBeeps(1);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -612,7 +617,7 @@ static void subTaskMotorUpdate(void)
|
||||||
startTime = micros();
|
startTime = micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
mixTable(currentPidProfile);
|
mixTable(currentPidProfile->vbatPidCompensation);
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
// motor outputs are used as sources for servo mixing, so motors must be calculated using mixTable() before servos.
|
// motor outputs are used as sources for servo mixing, so motors must be calculated using mixTable() before servos.
|
||||||
|
@ -621,9 +626,8 @@ static void subTaskMotorUpdate(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (motorControlEnable) {
|
|
||||||
writeMotors();
|
writeMotors();
|
||||||
}
|
|
||||||
DEBUG_SET(DEBUG_PIDLOOP, 3, micros() - startTime);
|
DEBUG_SET(DEBUG_PIDLOOP, 3, micros() - startTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -27,8 +27,6 @@ extern int16_t magHold;
|
||||||
extern bool isRXDataNew;
|
extern bool isRXDataNew;
|
||||||
extern int16_t headFreeModeHold;
|
extern int16_t headFreeModeHold;
|
||||||
|
|
||||||
extern uint8_t motorControlEnable;
|
|
||||||
|
|
||||||
typedef struct throttleCorrectionConfig_s {
|
typedef struct throttleCorrectionConfig_s {
|
||||||
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
|
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
|
||||||
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
||||||
|
@ -40,6 +38,8 @@ union rollAndPitchTrims_u;
|
||||||
void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta);
|
void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta);
|
||||||
void handleInflightCalibrationStickPosition();
|
void handleInflightCalibrationStickPosition();
|
||||||
|
|
||||||
|
void resetArmingDisabled(void);
|
||||||
|
|
||||||
void disarm(void);
|
void disarm(void);
|
||||||
void tryArm(void);
|
void tryArm(void);
|
||||||
|
|
||||||
|
|
|
@ -137,8 +137,6 @@
|
||||||
void targetPreInit(void);
|
void targetPreInit(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern uint8_t motorControlEnable;
|
|
||||||
|
|
||||||
#ifdef SOFTSERIAL_LOOPBACK
|
#ifdef SOFTSERIAL_LOOPBACK
|
||||||
serialPort_t *loopbackPort;
|
serialPort_t *loopbackPort;
|
||||||
#endif
|
#endif
|
||||||
|
@ -266,6 +264,20 @@ void init(void)
|
||||||
ensureEEPROMContainsValidData();
|
ensureEEPROMContainsValidData();
|
||||||
readEEPROM();
|
readEEPROM();
|
||||||
|
|
||||||
|
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
|
||||||
|
// If F4 Overclocking is set and System core clock is not correct a reset is forced
|
||||||
|
if (systemConfig()->cpu_overclock && SystemCoreClock != OC_FREQUENCY_HZ) {
|
||||||
|
*((uint32_t *)0x2001FFF8) = 0xBABEFACE; // 128KB SRAM STM32F4XX
|
||||||
|
__disable_irq();
|
||||||
|
NVIC_SystemReset();
|
||||||
|
} else if (!systemConfig()->cpu_overclock && SystemCoreClock == OC_FREQUENCY_HZ) {
|
||||||
|
*((uint32_t *)0x2001FFF8) = 0x0; // 128KB SRAM STM32F4XX
|
||||||
|
__disable_irq();
|
||||||
|
NVIC_SystemReset();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||||
|
|
||||||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||||
|
@ -481,7 +493,7 @@ void init(void)
|
||||||
|
|
||||||
if (!sensorsAutodetect()) {
|
if (!sensorsAutodetect()) {
|
||||||
// if gyro was not detected due to whatever reason, notify and don't arm.
|
// if gyro was not detected due to whatever reason, notify and don't arm.
|
||||||
failureLedCode(FAILURE_MISSING_ACC, 2);
|
indicateFailure(FAILURE_MISSING_ACC, 2);
|
||||||
setArmingDisabled(ARMING_DISABLED_NO_GYRO);
|
setArmingDisabled(ARMING_DISABLED_NO_GYRO);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -632,7 +644,7 @@ void init(void)
|
||||||
if (mixerConfig()->mixerMode == MIXER_GIMBAL) {
|
if (mixerConfig()->mixerMode == MIXER_GIMBAL) {
|
||||||
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
|
||||||
}
|
}
|
||||||
gyroStartCalibration();
|
gyroStartCalibration(false);
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
|
||||||
#endif
|
#endif
|
||||||
|
@ -695,7 +707,7 @@ void init(void)
|
||||||
|
|
||||||
// Latch active features AGAIN since some may be modified by init().
|
// Latch active features AGAIN since some may be modified by init().
|
||||||
latchActiveFeatures();
|
latchActiveFeatures();
|
||||||
motorControlEnable = true;
|
pwmEnableMotors();
|
||||||
|
|
||||||
#ifdef USE_OSD_SLAVE
|
#ifdef USE_OSD_SLAVE
|
||||||
osdSlaveTasksInit();
|
osdSlaveTasksInit();
|
||||||
|
|
|
@ -840,17 +840,32 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
|
|
||||||
#ifdef OSD
|
#ifdef OSD
|
||||||
// OSD specific, not applicable to OSD slaves.
|
// OSD specific, not applicable to OSD slaves.
|
||||||
|
|
||||||
|
// Configuration
|
||||||
sbufWriteU8(dst, osdConfig()->units);
|
sbufWriteU8(dst, osdConfig()->units);
|
||||||
|
|
||||||
|
// Alarms
|
||||||
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
sbufWriteU8(dst, osdConfig()->rssi_alarm);
|
||||||
sbufWriteU16(dst, osdConfig()->cap_alarm);
|
sbufWriteU16(dst, osdConfig()->cap_alarm);
|
||||||
sbufWriteU16(dst, osdConfig()->time_alarm);
|
sbufWriteU16(dst, 0);
|
||||||
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
sbufWriteU16(dst, osdConfig()->alt_alarm);
|
||||||
|
|
||||||
|
// Element position and visibility
|
||||||
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
|
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
|
||||||
sbufWriteU16(dst, osdConfig()->item_pos[i]);
|
sbufWriteU16(dst, osdConfig()->item_pos[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Post flight statistics
|
||||||
|
sbufWriteU8(dst, OSD_STAT_COUNT);
|
||||||
for (int i = 0; i < OSD_STAT_COUNT; i++ ) {
|
for (int i = 0; i < OSD_STAT_COUNT; i++ ) {
|
||||||
sbufWriteU8(dst, osdConfig()->enabled_stats[i]);
|
sbufWriteU8(dst, osdConfig()->enabled_stats[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Timers
|
||||||
|
sbufWriteU8(dst, OSD_TIMER_COUNT);
|
||||||
|
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
||||||
|
sbufWriteU16(dst, osdConfig()->timers[i]);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -1185,7 +1200,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_RX_MAP:
|
case MSP_RX_MAP:
|
||||||
sbufWriteData(dst, rxConfig()->rcmap, MAX_MAPPABLE_RX_INPUTS);
|
sbufWriteData(dst, rxConfig()->rcmap, RX_MAPPABLE_CHANNEL_COUNT);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_BF_CONFIG:
|
case MSP_BF_CONFIG:
|
||||||
|
@ -1940,7 +1955,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_RX_MAP:
|
case MSP_SET_RX_MAP:
|
||||||
for (int i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
|
for (int i = 0; i < RX_MAPPABLE_CHANNEL_COUNT; i++) {
|
||||||
rxConfigMutable()->rcmap[i] = sbufReadU8(src);
|
rxConfigMutable()->rcmap[i] = sbufReadU8(src);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -2154,11 +2169,23 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
#endif
|
#endif
|
||||||
#if defined(OSD)
|
#if defined(OSD)
|
||||||
osdConfigMutable()->units = sbufReadU8(src);
|
osdConfigMutable()->units = sbufReadU8(src);
|
||||||
|
|
||||||
|
// Alarms
|
||||||
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
||||||
osdConfigMutable()->cap_alarm = sbufReadU16(src);
|
osdConfigMutable()->cap_alarm = sbufReadU16(src);
|
||||||
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
sbufReadU16(src); // Skip unused (previously fly timer)
|
||||||
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
||||||
#endif
|
#endif
|
||||||
|
} else if ((int8_t)addr == -2) {
|
||||||
|
#if defined(OSD)
|
||||||
|
// Timers
|
||||||
|
uint8_t index = sbufReadU8(src);
|
||||||
|
if (index > OSD_TIMER_COUNT) {
|
||||||
|
return MSP_RESULT_ERROR;
|
||||||
|
}
|
||||||
|
osdConfigMutable()->timers[index] = sbufReadU16(src);
|
||||||
|
#endif
|
||||||
|
return MSP_RESULT_ERROR;
|
||||||
} else {
|
} else {
|
||||||
#if defined(OSD)
|
#if defined(OSD)
|
||||||
const uint16_t value = sbufReadU16(src);
|
const uint16_t value = sbufReadU16(src);
|
||||||
|
@ -2172,6 +2199,8 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
} else if (addr < OSD_ITEM_COUNT) {
|
} else if (addr < OSD_ITEM_COUNT) {
|
||||||
/* Set element positions */
|
/* Set element positions */
|
||||||
osdConfigMutable()->item_pos[addr] = value;
|
osdConfigMutable()->item_pos[addr] = value;
|
||||||
|
} else {
|
||||||
|
return MSP_RESULT_ERROR;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
return MSP_RESULT_ERROR;
|
return MSP_RESULT_ERROR;
|
||||||
|
|
|
@ -147,6 +147,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
tryArm();
|
tryArm();
|
||||||
} else {
|
} else {
|
||||||
// Disarming via ARM BOX
|
// Disarming via ARM BOX
|
||||||
|
resetArmingDisabled();
|
||||||
|
|
||||||
if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) {
|
if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) {
|
||||||
rcDisarmTicks++;
|
rcDisarmTicks++;
|
||||||
|
@ -187,7 +188,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
|
|
||||||
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
|
||||||
// GYRO calibration
|
// GYRO calibration
|
||||||
gyroStartCalibration();
|
gyroStartCalibration(false);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
|
@ -232,6 +233,8 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
||||||
tryArm();
|
tryArm();
|
||||||
|
|
||||||
return;
|
return;
|
||||||
|
} else {
|
||||||
|
resetArmingDisabled();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -29,6 +29,13 @@ uint16_t flightModeFlags = 0;
|
||||||
|
|
||||||
static uint32_t enabledSensors = 0;
|
static uint32_t enabledSensors = 0;
|
||||||
|
|
||||||
|
#if defined(OSD) || !defined(MINIMAL_CLI)
|
||||||
|
const char *armingDisableFlagNames[]= {
|
||||||
|
"NOGYRO", "FAILSAFE", "BOXFAILSAFE", "THROTTLE",
|
||||||
|
"ANGLE", "LOAD", "CALIB", "CLI", "CMS", "OSD", "BST"
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
static armingDisableFlags_e armingDisableFlags = 0;
|
static armingDisableFlags_e armingDisableFlags = 0;
|
||||||
|
|
||||||
void setArmingDisabled(armingDisableFlags_e flag)
|
void setArmingDisabled(armingDisableFlags_e flag)
|
||||||
|
|
|
@ -47,6 +47,11 @@ typedef enum {
|
||||||
ARMING_DISABLED_BST = (1 << 10),
|
ARMING_DISABLED_BST = (1 << 10),
|
||||||
} armingDisableFlags_e;
|
} armingDisableFlags_e;
|
||||||
|
|
||||||
|
#define NUM_ARMING_DISABLE_FLAGS 11
|
||||||
|
#if defined(OSD) || !defined(MINIMAL_CLI)
|
||||||
|
extern const char *armingDisableFlagNames[NUM_ARMING_DISABLE_FLAGS];
|
||||||
|
#endif
|
||||||
|
|
||||||
void setArmingDisabled(armingDisableFlags_e flag);
|
void setArmingDisabled(armingDisableFlags_e flag);
|
||||||
void unsetArmingDisabled(armingDisableFlags_e flag);
|
void unsetArmingDisabled(armingDisableFlags_e flag);
|
||||||
bool isArmingDisabled(void);
|
bool isArmingDisabled(void);
|
||||||
|
|
|
@ -634,13 +634,15 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
|
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
|
||||||
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
||||||
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_OSD_CONFIG, offsetof(osdConfig_t, time_alarm) },
|
|
||||||
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
||||||
|
|
||||||
|
{ "osd_tim1", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_1]) },
|
||||||
|
{ "osd_tim2", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_2]) },
|
||||||
|
|
||||||
{ "osd_vbat_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_VOLTAGE]) },
|
{ "osd_vbat_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_VOLTAGE]) },
|
||||||
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_VALUE]) },
|
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_VALUE]) },
|
||||||
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYTIME]) },
|
{ "osd_tim_1_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ITEM_TIMER_1]) },
|
||||||
{ "osd_ontimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ONTIME]) },
|
{ "osd_tim_2_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ITEM_TIMER_2]) },
|
||||||
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYMODE]) },
|
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYMODE]) },
|
||||||
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_THROTTLE_POS]) },
|
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_THROTTLE_POS]) },
|
||||||
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_VTX_CHANNEL]) },
|
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_VTX_CHANNEL]) },
|
||||||
|
@ -668,7 +670,6 @@ const clivalue_t valueTable[] = {
|
||||||
{ "osd_pit_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_PITCH_ANGLE]) },
|
{ "osd_pit_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_PITCH_ANGLE]) },
|
||||||
{ "osd_rol_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ROLL_ANGLE]) },
|
{ "osd_rol_ang_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ROLL_ANGLE]) },
|
||||||
{ "osd_battery_usage_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_USAGE]) },
|
{ "osd_battery_usage_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_USAGE]) },
|
||||||
{ "osd_arm_time_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ARMED_TIME]) },
|
|
||||||
{ "osd_disarmed_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_DISARMED]) },
|
{ "osd_disarmed_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_DISARMED]) },
|
||||||
{ "osd_nheading_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_NUMERICAL_HEADING]) },
|
{ "osd_nheading_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_NUMERICAL_HEADING]) },
|
||||||
{ "osd_nvario_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_NUMERICAL_VARIO]) },
|
{ "osd_nvario_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_NUMERICAL_VARIO]) },
|
||||||
|
@ -684,9 +685,9 @@ const clivalue_t valueTable[] = {
|
||||||
{ "osd_stat_max_alt", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MAX_ALTITUDE])},
|
{ "osd_stat_max_alt", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_MAX_ALTITUDE])},
|
||||||
{ "osd_stat_bbox", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_BLACKBOX])},
|
{ "osd_stat_bbox", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_BLACKBOX])},
|
||||||
{ "osd_stat_endbatt", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_END_BATTERY])},
|
{ "osd_stat_endbatt", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_END_BATTERY])},
|
||||||
{ "osd_stat_flytime", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_FLYTIME])},
|
|
||||||
{ "osd_stat_armtime", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_ARMEDTIME])},
|
|
||||||
{ "osd_stat_bb_no", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_BLACKBOX_NUMBER])},
|
{ "osd_stat_bb_no", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_BLACKBOX_NUMBER])},
|
||||||
|
{ "osd_stat_tim_1", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_TIMER_1])},
|
||||||
|
{ "osd_stat_tim_2", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats[OSD_STAT_TIMER_2])},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_SYSTEM_CONFIG
|
// PG_SYSTEM_CONFIG
|
||||||
|
@ -694,6 +695,9 @@ const clivalue_t valueTable[] = {
|
||||||
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
|
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
|
||||||
#endif
|
#endif
|
||||||
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },
|
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },
|
||||||
|
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
|
||||||
|
{ "cpu_overclock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, cpu_overclock) },
|
||||||
|
#endif
|
||||||
|
|
||||||
// PG_VTX_CONFIG
|
// PG_VTX_CONFIG
|
||||||
#ifdef VTX_RTC6705
|
#ifdef VTX_RTC6705
|
||||||
|
|
|
@ -352,7 +352,7 @@ void initEscEndpoints(void) {
|
||||||
else
|
else
|
||||||
motorOutputLow = DSHOT_MIN_THROTTLE + ((DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue);
|
motorOutputLow = DSHOT_MIN_THROTTLE + ((DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue);
|
||||||
motorOutputHigh = DSHOT_MAX_THROTTLE;
|
motorOutputHigh = DSHOT_MAX_THROTTLE;
|
||||||
deadbandMotor3dHigh = DSHOT_3D_DEADBAND_HIGH + ((DSHOT_MAX_THROTTLE - DSHOT_3D_DEADBAND_HIGH) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue); // TODO - Not working yet !! Mixer requires some throttle rescaling changes
|
deadbandMotor3dHigh = DSHOT_3D_DEADBAND_HIGH + ((DSHOT_MAX_THROTTLE - DSHOT_3D_DEADBAND_HIGH) / 100.0f) * CONVERT_PARAMETER_TO_PERCENT(motorConfig()->digitalIdleOffsetValue);
|
||||||
deadbandMotor3dLow = DSHOT_3D_DEADBAND_LOW;
|
deadbandMotor3dLow = DSHOT_3D_DEADBAND_LOW;
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
@ -469,10 +469,9 @@ void writeMotors(void)
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < motorCount; i++) {
|
||||||
pwmWriteMotor(i, motor[i]);
|
pwmWriteMotor(i, motor[i]);
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
pwmCompleteMotorUpdate(motorCount);
|
pwmCompleteMotorUpdate(motorCount);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void writeAllMotors(int16_t mc)
|
static void writeAllMotors(int16_t mc)
|
||||||
{
|
{
|
||||||
|
@ -497,39 +496,37 @@ void stopPwmAllMotors(void)
|
||||||
delayMicroseconds(1500);
|
delayMicroseconds(1500);
|
||||||
}
|
}
|
||||||
|
|
||||||
void mixTable(pidProfile_t *pidProfile)
|
float throttle = 0;
|
||||||
{
|
|
||||||
// Scale roll/pitch/yaw uniformly to fit within throttle range
|
|
||||||
// Initial mixer concept by bdoiron74 reused and optimized for Air Mode
|
|
||||||
float throttle = 0, currentThrottleInputRange = 0;
|
|
||||||
float motorOutputMin, motorOutputMax;
|
float motorOutputMin, motorOutputMax;
|
||||||
static uint16_t throttlePrevious = 0; // Store the last throttle direction for deadband transitions
|
|
||||||
bool mixerInversion = false;
|
bool mixerInversion = false;
|
||||||
|
float motorOutputRange;
|
||||||
|
|
||||||
|
void calculateThrottleAndCurrentMotorEndpoints(void)
|
||||||
|
{
|
||||||
|
static uint16_t throttlePrevious = 0; // Store the last throttle direction for deadband transitions
|
||||||
|
float currentThrottleInputRange = 0;
|
||||||
|
|
||||||
// Find min and max throttle based on condition.
|
|
||||||
if(feature(FEATURE_3D)) {
|
if(feature(FEATURE_3D)) {
|
||||||
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
||||||
|
|
||||||
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Out of band handling
|
if((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) {
|
||||||
motorOutputMax = deadbandMotor3dLow;
|
motorOutputMax = deadbandMotor3dLow;
|
||||||
motorOutputMin = motorOutputLow;
|
motorOutputMin = motorOutputLow;
|
||||||
throttlePrevious = rcCommand[THROTTLE];
|
|
||||||
throttle = rcCommand[THROTTLE] - rxConfig()->mincheck;
|
|
||||||
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
||||||
if(isMotorProtocolDshot()) mixerInversion = true;
|
if(isMotorProtocolDshot()) mixerInversion = true;
|
||||||
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) { // Positive handling
|
} else if(rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) {
|
||||||
motorOutputMax = motorOutputHigh;
|
motorOutputMax = motorOutputHigh;
|
||||||
motorOutputMin = deadbandMotor3dHigh;
|
motorOutputMin = deadbandMotor3dHigh;
|
||||||
throttlePrevious = rcCommand[THROTTLE];
|
throttlePrevious = rcCommand[THROTTLE];
|
||||||
throttle = rcCommand[THROTTLE] - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
throttle = rcCommand[THROTTLE] - rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||||
currentThrottleInputRange = rcCommandThrottleRange3dHigh;
|
currentThrottleInputRange = rcCommandThrottleRange3dHigh;
|
||||||
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive
|
} else if((throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) {
|
||||||
motorOutputMax = deadbandMotor3dLow;
|
motorOutputMax = deadbandMotor3dLow;
|
||||||
motorOutputMin = motorOutputLow;
|
motorOutputMin = motorOutputLow;
|
||||||
throttle = rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
throttle = rxConfig()->midrc - flight3DConfig()->deadband3d_throttle;
|
||||||
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
currentThrottleInputRange = rcCommandThrottleRange3dLow;
|
||||||
if(isMotorProtocolDshot()) mixerInversion = true;
|
if(isMotorProtocolDshot()) mixerInversion = true;
|
||||||
} else { // Deadband handling from positive to negative
|
} else {
|
||||||
motorOutputMax = motorOutputHigh;
|
motorOutputMax = motorOutputHigh;
|
||||||
motorOutputMin = deadbandMotor3dHigh;
|
motorOutputMin = deadbandMotor3dHigh;
|
||||||
throttle = 0;
|
throttle = 0;
|
||||||
|
@ -543,7 +540,53 @@ void mixTable(pidProfile_t *pidProfile)
|
||||||
}
|
}
|
||||||
|
|
||||||
throttle = constrainf(throttle / currentThrottleInputRange, 0.0f, 1.0f);
|
throttle = constrainf(throttle / currentThrottleInputRange, 0.0f, 1.0f);
|
||||||
const float motorOutputRange = motorOutputMax - motorOutputMin;
|
motorOutputRange = motorOutputMax - motorOutputMin;
|
||||||
|
}
|
||||||
|
|
||||||
|
void applyMixToMotors(float motorMix[MAX_SUPPORTED_MOTORS]) {
|
||||||
|
// Now add in the desired throttle, but keep in a range that doesn't clip adjusted
|
||||||
|
// roll/pitch/yaw. This could move throttle down, but also up for those low throttle flips.
|
||||||
|
for (uint32_t i = 0; i < motorCount; i++) {
|
||||||
|
float motorOutput = motorOutputMin + motorOutputRange * (motorMix[i] + (throttle * currentMixer[i].throttle));
|
||||||
|
|
||||||
|
// Dshot works exactly opposite in lower 3D section.
|
||||||
|
if (mixerInversion) {
|
||||||
|
motorOutput = motorOutputMin + (motorOutputMax - motorOutput);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (failsafeIsActive()) {
|
||||||
|
if (isMotorProtocolDshot()) {
|
||||||
|
motorOutput = (motorOutput < motorOutputMin) ? disarmMotorOutput : motorOutput; // Prevent getting into special reserved range
|
||||||
|
}
|
||||||
|
|
||||||
|
motorOutput = constrain(motorOutput, disarmMotorOutput, motorOutputMax);
|
||||||
|
} else {
|
||||||
|
motorOutput = constrain(motorOutput, motorOutputMin, motorOutputMax);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Motor stop handling
|
||||||
|
if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) {
|
||||||
|
if (((rcData[THROTTLE]) < rxConfig()->mincheck)) {
|
||||||
|
motorOutput = disarmMotorOutput;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
motor[i] = motorOutput;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Disarmed mode
|
||||||
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
|
for (int i = 0; i < motorCount; i++) {
|
||||||
|
motor[i] = motor_disarmed[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void mixTable(uint8_t vbatPidCompensation)
|
||||||
|
{
|
||||||
|
// Find min and max throttle based on conditions. Throttle has to be known before mixing
|
||||||
|
calculateThrottleAndCurrentMotorEndpoints();
|
||||||
|
|
||||||
|
float motorMix[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
// Calculate and Limit the PIDsum
|
// Calculate and Limit the PIDsum
|
||||||
const float scaledAxisPidRoll =
|
const float scaledAxisPidRoll =
|
||||||
|
@ -554,15 +597,13 @@ void mixTable(pidProfile_t *pidProfile)
|
||||||
constrainf((axisPID_P[FD_YAW] + axisPID_I[FD_YAW]) / PID_MIXER_SCALING, -pidSumLimitYaw, pidSumLimitYaw);
|
constrainf((axisPID_P[FD_YAW] + axisPID_I[FD_YAW]) / PID_MIXER_SCALING, -pidSumLimitYaw, pidSumLimitYaw);
|
||||||
|
|
||||||
// Calculate voltage compensation
|
// Calculate voltage compensation
|
||||||
const float vbatCompensationFactor = (pidProfile->vbatPidCompensation) ? calculateVbatPidCompensation() : 1.0f;
|
const float vbatCompensationFactor = (vbatPidCompensation) ? calculateVbatPidCompensation() : 1.0f;
|
||||||
|
|
||||||
// Find roll/pitch/yaw desired output
|
// Find roll/pitch/yaw desired output
|
||||||
float motorMix[MAX_SUPPORTED_MOTORS];
|
|
||||||
float motorMixMax = 0, motorMixMin = 0;
|
float motorMixMax = 0, motorMixMin = 0;
|
||||||
const int yawDirection = GET_DIRECTION(mixerConfig()->yaw_motors_reversed);
|
const int yawDirection = GET_DIRECTION(mixerConfig()->yaw_motors_reversed);
|
||||||
int motorDirection = GET_DIRECTION(isMotorsReversed());
|
int motorDirection = GET_DIRECTION(isMotorsReversed());
|
||||||
|
|
||||||
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < motorCount; i++) {
|
||||||
float mix =
|
float mix =
|
||||||
scaledAxisPidRoll * currentMixer[i].roll * (motorDirection) +
|
scaledAxisPidRoll * currentMixer[i].roll * (motorDirection) +
|
||||||
|
@ -598,41 +639,8 @@ void mixTable(pidProfile_t *pidProfile)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Now add in the desired throttle, but keep in a range that doesn't clip adjusted
|
// Apply the mix to motor endpoints
|
||||||
// roll/pitch/yaw. This could move throttle down, but also up for those low throttle flips.
|
applyMixToMotors(motorMix);
|
||||||
for (uint32_t i = 0; i < motorCount; i++) {
|
|
||||||
float motorOutput = motorOutputMin + motorOutputRange * (motorMix[i] + (throttle * currentMixer[i].throttle));
|
|
||||||
|
|
||||||
// Dshot works exactly opposite in lower 3D section.
|
|
||||||
if (mixerInversion) {
|
|
||||||
motorOutput = motorOutputMin + (motorOutputMax - motorOutput);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (failsafeIsActive()) {
|
|
||||||
if (isMotorProtocolDshot()) {
|
|
||||||
motorOutput = (motorOutput < motorOutputMin) ? disarmMotorOutput : motorOutput; // Prevent getting into special reserved range
|
|
||||||
}
|
|
||||||
|
|
||||||
motorOutput = constrain(motorOutput, disarmMotorOutput, motorOutputMax);
|
|
||||||
} else {
|
|
||||||
motorOutput = constrain(motorOutput, motorOutputMin, motorOutputMax);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Motor stop handling
|
|
||||||
if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isAirmodeActive()) {
|
|
||||||
if (((rcData[THROTTLE]) < rxConfig()->mincheck)) {
|
|
||||||
motorOutput = disarmMotorOutput;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
motor[i] = motorOutput;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Disarmed mode
|
|
||||||
if (!ARMING_FLAG(ARMED)) {
|
|
||||||
for (int i = 0; i < motorCount; i++) {
|
|
||||||
motor[i] = motor_disarmed[i];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
float convertExternalToMotor(uint16_t externalValue)
|
float convertExternalToMotor(uint16_t externalValue)
|
||||||
|
|
|
@ -116,7 +116,7 @@ void pidInitMixer(const struct pidProfile_s *pidProfile);
|
||||||
void mixerConfigureOutput(void);
|
void mixerConfigureOutput(void);
|
||||||
|
|
||||||
void mixerResetDisarmedMotors(void);
|
void mixerResetDisarmedMotors(void);
|
||||||
void mixTable(struct pidProfile_s *pidProfile);
|
void mixTable(uint8_t vbatPidCompensation);
|
||||||
void syncMotors(bool enabled);
|
void syncMotors(bool enabled);
|
||||||
void writeMotors(void);
|
void writeMotors(void);
|
||||||
void stopMotors(void);
|
void stopMotors(void);
|
||||||
|
|
|
@ -28,6 +28,7 @@
|
||||||
|
|
||||||
#include "fat_standard.h"
|
#include "fat_standard.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
|
||||||
#ifdef AFATFS_DEBUG
|
#ifdef AFATFS_DEBUG
|
||||||
#define ONLY_EXPOSE_FOR_TESTING
|
#define ONLY_EXPOSE_FOR_TESTING
|
||||||
|
@ -92,9 +93,6 @@
|
||||||
|
|
||||||
#define AFATFS_INTROSPEC_LOG_FILENAME "ASYNCFAT.LOG"
|
#define AFATFS_INTROSPEC_LOG_FILENAME "ASYNCFAT.LOG"
|
||||||
|
|
||||||
#define MIN(a, b) ((a) < (b) ? (a) : (b))
|
|
||||||
#define MAX(a, b) ((a) > (b) ? (a) : (b))
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
AFATFS_SAVE_DIRECTORY_NORMAL,
|
AFATFS_SAVE_DIRECTORY_NORMAL,
|
||||||
AFATFS_SAVE_DIRECTORY_FOR_CLOSE,
|
AFATFS_SAVE_DIRECTORY_FOR_CLOSE,
|
||||||
|
|
|
@ -78,7 +78,7 @@ PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
|
||||||
#define BEEPER_NAMES
|
#define BEEPER_NAMES
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define MAX_MULTI_BEEPS 20 //size limit for 'beep_multiBeeps[]'
|
#define MAX_MULTI_BEEPS 64 //size limit for 'beep_multiBeeps[]'
|
||||||
|
|
||||||
#define BEEPER_COMMAND_REPEAT 0xFE
|
#define BEEPER_COMMAND_REPEAT 0xFE
|
||||||
#define BEEPER_COMMAND_STOP 0xFF
|
#define BEEPER_COMMAND_STOP 0xFF
|
||||||
|
@ -151,11 +151,15 @@ static const uint8_t beep_gyroCalibrated[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
// array used for variable # of beeps (reporting GPS sat count, etc)
|
// array used for variable # of beeps (reporting GPS sat count, etc)
|
||||||
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
|
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 1];
|
||||||
|
|
||||||
#define BEEPER_CONFIRMATION_BEEP_DURATION 2
|
#define BEEPER_CONFIRMATION_BEEP_DURATION 2
|
||||||
#define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20
|
#define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20
|
||||||
|
|
||||||
|
#define BEEPER_WARNING_BEEP_1_DURATION 20
|
||||||
|
#define BEEPER_WARNING_BEEP_2_DURATION 5
|
||||||
|
#define BEEPER_WARNING_BEEP_GAP_DURATION 10
|
||||||
|
|
||||||
// Beeper off = 0 Beeper on = 1
|
// Beeper off = 0 Beeper on = 1
|
||||||
static uint8_t beeperIsOn = 0;
|
static uint8_t beeperIsOn = 0;
|
||||||
|
|
||||||
|
@ -270,25 +274,43 @@ void beeperSilence(void)
|
||||||
|
|
||||||
currentBeeperEntry = NULL;
|
currentBeeperEntry = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Emits the given number of 20ms beeps (with 200ms spacing).
|
* Emits the given number of 20ms beeps (with 200ms spacing).
|
||||||
* This function returns immediately (does not block).
|
* This function returns immediately (does not block).
|
||||||
*/
|
*/
|
||||||
void beeperConfirmationBeeps(uint8_t beepCount)
|
void beeperConfirmationBeeps(uint8_t beepCount)
|
||||||
{
|
{
|
||||||
int i;
|
uint32_t i = 0;
|
||||||
int cLimit;
|
uint32_t cLimit = beepCount * 2;
|
||||||
|
if (cLimit > MAX_MULTI_BEEPS) {
|
||||||
i = 0;
|
cLimit = MAX_MULTI_BEEPS;
|
||||||
cLimit = beepCount * 2;
|
}
|
||||||
if(cLimit > MAX_MULTI_BEEPS)
|
|
||||||
cLimit = MAX_MULTI_BEEPS; //stay within array size
|
|
||||||
do {
|
do {
|
||||||
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION; // 20ms beep
|
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION;
|
||||||
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_GAP_DURATION; // 200ms pause
|
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_GAP_DURATION;
|
||||||
} while (i < cLimit);
|
} while (i < cLimit);
|
||||||
beep_multiBeeps[i] = BEEPER_COMMAND_STOP; //sequence end
|
beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
|
||||||
beeper(BEEPER_MULTI_BEEPS); //initiate sequence
|
|
||||||
|
beeper(BEEPER_MULTI_BEEPS);
|
||||||
|
}
|
||||||
|
|
||||||
|
void beeperWarningBeeps(uint8_t beepCount)
|
||||||
|
{
|
||||||
|
uint32_t i = 0;
|
||||||
|
uint32_t cLimit = beepCount * 4;
|
||||||
|
if (cLimit >= MAX_MULTI_BEEPS) {
|
||||||
|
cLimit = MAX_MULTI_BEEPS;
|
||||||
|
}
|
||||||
|
do {
|
||||||
|
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_1_DURATION;
|
||||||
|
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_GAP_DURATION;
|
||||||
|
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_2_DURATION;
|
||||||
|
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_GAP_DURATION;
|
||||||
|
} while (i < cLimit);
|
||||||
|
beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
|
||||||
|
|
||||||
|
beeper(BEEPER_MULTI_BEEPS);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -444,6 +466,7 @@ bool isBeeperOn(void)
|
||||||
void beeper(beeperMode_e mode) {UNUSED(mode);}
|
void beeper(beeperMode_e mode) {UNUSED(mode);}
|
||||||
void beeperSilence(void) {}
|
void beeperSilence(void) {}
|
||||||
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
|
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
|
||||||
|
void beeperWarningBeeps(uint8_t beepCount) {UNUSED(beepCount);}
|
||||||
void beeperUpdate(timeUs_t currentTimeUs) {UNUSED(currentTimeUs);}
|
void beeperUpdate(timeUs_t currentTimeUs) {UNUSED(currentTimeUs);}
|
||||||
uint32_t getArmingBeepTimeMicros(void) {return 0;}
|
uint32_t getArmingBeepTimeMicros(void) {return 0;}
|
||||||
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}
|
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}
|
||||||
|
|
|
@ -61,6 +61,7 @@ void beeper(beeperMode_e mode);
|
||||||
void beeperSilence(void);
|
void beeperSilence(void);
|
||||||
void beeperUpdate(timeUs_t currentTimeUs);
|
void beeperUpdate(timeUs_t currentTimeUs);
|
||||||
void beeperConfirmationBeeps(uint8_t beepCount);
|
void beeperConfirmationBeeps(uint8_t beepCount);
|
||||||
|
void beeperWarningBeeps(uint8_t beepCount);
|
||||||
uint32_t getArmingBeepTimeMicros(void);
|
uint32_t getArmingBeepTimeMicros(void);
|
||||||
beeperMode_e beeperModeForTableIndex(int idx);
|
beeperMode_e beeperModeForTableIndex(int idx);
|
||||||
const char *beeperNameForTableIndex(int idx);
|
const char *beeperNameForTableIndex(int idx);
|
||||||
|
|
|
@ -89,6 +89,12 @@
|
||||||
|
|
||||||
#define VIDEO_BUFFER_CHARS_PAL 480
|
#define VIDEO_BUFFER_CHARS_PAL 480
|
||||||
|
|
||||||
|
const char * const osdTimerSourceNames[] = {
|
||||||
|
"ON TIME ",
|
||||||
|
"TOTAL ARM",
|
||||||
|
"LAST ARM "
|
||||||
|
};
|
||||||
|
|
||||||
// Blink control
|
// Blink control
|
||||||
|
|
||||||
static bool blinkState = true;
|
static bool blinkState = true;
|
||||||
|
@ -106,7 +112,7 @@ static uint32_t blinkBits[(OSD_ITEM_COUNT + 31)/32];
|
||||||
#define IS_LO(X) (rcData[X] < 1250)
|
#define IS_LO(X) (rcData[X] < 1250)
|
||||||
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
|
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
|
||||||
|
|
||||||
static uint16_t flyTime = 0;
|
static timeUs_t flyTime = 0;
|
||||||
static uint8_t statRssi;
|
static uint8_t statRssi;
|
||||||
|
|
||||||
typedef struct statistic_s {
|
typedef struct statistic_s {
|
||||||
|
@ -116,7 +122,7 @@ typedef struct statistic_s {
|
||||||
int16_t min_rssi;
|
int16_t min_rssi;
|
||||||
int16_t max_altitude;
|
int16_t max_altitude;
|
||||||
int16_t max_distance;
|
int16_t max_distance;
|
||||||
uint16_t armed_time;
|
timeUs_t armed_time;
|
||||||
} statistic_t;
|
} statistic_t;
|
||||||
|
|
||||||
static statistic_t stats;
|
static statistic_t stats;
|
||||||
|
@ -128,7 +134,6 @@ static uint8_t armState;
|
||||||
|
|
||||||
static displayPort_t *osdDisplayPort;
|
static displayPort_t *osdDisplayPort;
|
||||||
|
|
||||||
|
|
||||||
#define AH_MAX_PITCH 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees
|
#define AH_MAX_PITCH 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees
|
||||||
#define AH_MAX_ROLL 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees
|
#define AH_MAX_ROLL 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees
|
||||||
#define AH_SIDEBAR_WIDTH_POS 7
|
#define AH_SIDEBAR_WIDTH_POS 7
|
||||||
|
@ -227,6 +232,65 @@ static uint8_t osdGetDirectionSymbolFromHeading(int heading)
|
||||||
return SYM_ARROW_SOUTH + heading;
|
return SYM_ARROW_SOUTH + heading;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static char osdGetTimerSymbol(osd_timer_source_e src)
|
||||||
|
{
|
||||||
|
switch (src) {
|
||||||
|
case OSD_TIMER_SRC_ON:
|
||||||
|
return SYM_ON_M;
|
||||||
|
case OSD_TIMER_SRC_TOTAL_ARMED:
|
||||||
|
case OSD_TIMER_SRC_LAST_ARMED:
|
||||||
|
return SYM_FLY_M;
|
||||||
|
default:
|
||||||
|
return ' ';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static timeUs_t osdGetTimerValue(osd_timer_source_e src)
|
||||||
|
{
|
||||||
|
switch (src) {
|
||||||
|
case OSD_TIMER_SRC_ON:
|
||||||
|
return micros();
|
||||||
|
case OSD_TIMER_SRC_TOTAL_ARMED:
|
||||||
|
return flyTime;
|
||||||
|
case OSD_TIMER_SRC_LAST_ARMED:
|
||||||
|
return stats.armed_time;
|
||||||
|
default:
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time)
|
||||||
|
{
|
||||||
|
int seconds = time / 1000000;
|
||||||
|
const int minutes = seconds / 60;
|
||||||
|
seconds = seconds % 60;
|
||||||
|
|
||||||
|
switch (precision) {
|
||||||
|
case OSD_TIMER_PREC_SECOND:
|
||||||
|
default:
|
||||||
|
tfp_sprintf(buff, "%02d:%02d", minutes, seconds);
|
||||||
|
break;
|
||||||
|
case OSD_TIMER_PREC_HUNDREDTHS:
|
||||||
|
{
|
||||||
|
const int hundredths = (time / 10000) % 100;
|
||||||
|
tfp_sprintf(buff, "%02d:%02d.%02d", minutes, seconds, hundredths);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED void osdFormatTimer(char *buff, bool showSymbol, int timerIndex)
|
||||||
|
{
|
||||||
|
const uint16_t timer = osdConfig()->timers[timerIndex];
|
||||||
|
const uint8_t src = OSD_TIMER_SRC(timer);
|
||||||
|
|
||||||
|
if (showSymbol) {
|
||||||
|
*(buff++) = osdGetTimerSymbol(src);
|
||||||
|
}
|
||||||
|
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PRECISION(timer), osdGetTimerValue(src));
|
||||||
|
}
|
||||||
|
|
||||||
static void osdDrawSingleElement(uint8_t item)
|
static void osdDrawSingleElement(uint8_t item)
|
||||||
{
|
{
|
||||||
if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) {
|
if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) {
|
||||||
|
@ -236,7 +300,7 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
|
uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
|
||||||
uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]);
|
uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]);
|
||||||
uint8_t elemOffsetX = 0;
|
uint8_t elemOffsetX = 0;
|
||||||
char buff[32];
|
char buff[OSD_ELEMENT_BUFFER_LENGTH];
|
||||||
|
|
||||||
switch (item) {
|
switch (item) {
|
||||||
case OSD_RSSI_VALUE:
|
case OSD_RSSI_VALUE:
|
||||||
|
@ -351,24 +415,14 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case OSD_ONTIME:
|
case OSD_ITEM_TIMER_1:
|
||||||
|
case OSD_ITEM_TIMER_2:
|
||||||
{
|
{
|
||||||
const uint32_t seconds = micros() / 1000000;
|
const int timer = item - OSD_ITEM_TIMER_1;
|
||||||
buff[0] = SYM_ON_M;
|
osdFormatTimer(buff, true, timer);
|
||||||
tfp_sprintf(buff + 1, "%02d:%02d", seconds / 60, seconds % 60);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case OSD_FLYTIME:
|
|
||||||
buff[0] = SYM_FLY_M;
|
|
||||||
tfp_sprintf(buff + 1, "%02d:%02d", flyTime / 60, flyTime % 60);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OSD_ARMED_TIME:
|
|
||||||
buff[0] = SYM_FLY_M;
|
|
||||||
tfp_sprintf(buff + 1, "%02d:%02d", stats.armed_time / 60, stats.armed_time % 60);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case OSD_FLYMODE:
|
case OSD_FLYMODE:
|
||||||
{
|
{
|
||||||
char *p = "ACRO";
|
char *p = "ACRO";
|
||||||
|
@ -520,6 +574,19 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
}
|
}
|
||||||
|
|
||||||
case OSD_WARNINGS:
|
case OSD_WARNINGS:
|
||||||
|
/* Show common reason for arming being disabled */
|
||||||
|
if (IS_RC_MODE_ACTIVE(BOXARM) && isArmingDisabled()) {
|
||||||
|
const armingDisableFlags_e flags = getArmingDisableFlags();
|
||||||
|
for (int i = 0; i < NUM_ARMING_DISABLE_FLAGS; i++) {
|
||||||
|
if (flags & (1 << i)) {
|
||||||
|
tfp_sprintf(buff, "%s", armingDisableFlagNames[i]);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Show battery state warning */
|
||||||
switch (getBatteryState()) {
|
switch (getBatteryState()) {
|
||||||
case BATTERY_WARNING:
|
case BATTERY_WARNING:
|
||||||
tfp_sprintf(buff, "LOW BATTERY");
|
tfp_sprintf(buff, "LOW BATTERY");
|
||||||
|
@ -530,6 +597,7 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
/* Show visual beeper if battery is OK */
|
||||||
if (showVisualBeeper) {
|
if (showVisualBeeper) {
|
||||||
tfp_sprintf(buff, " * * * *");
|
tfp_sprintf(buff, " * * * *");
|
||||||
} else {
|
} else {
|
||||||
|
@ -645,8 +713,8 @@ static void osdDrawElements(void)
|
||||||
osdDrawSingleElement(OSD_MAIN_BATT_VOLTAGE);
|
osdDrawSingleElement(OSD_MAIN_BATT_VOLTAGE);
|
||||||
osdDrawSingleElement(OSD_RSSI_VALUE);
|
osdDrawSingleElement(OSD_RSSI_VALUE);
|
||||||
osdDrawSingleElement(OSD_CROSSHAIRS);
|
osdDrawSingleElement(OSD_CROSSHAIRS);
|
||||||
osdDrawSingleElement(OSD_FLYTIME);
|
osdDrawSingleElement(OSD_ITEM_TIMER_1);
|
||||||
osdDrawSingleElement(OSD_ONTIME);
|
osdDrawSingleElement(OSD_ITEM_TIMER_2);
|
||||||
osdDrawSingleElement(OSD_FLYMODE);
|
osdDrawSingleElement(OSD_FLYMODE);
|
||||||
osdDrawSingleElement(OSD_THROTTLE_POS);
|
osdDrawSingleElement(OSD_THROTTLE_POS);
|
||||||
osdDrawSingleElement(OSD_VTX_CHANNEL);
|
osdDrawSingleElement(OSD_VTX_CHANNEL);
|
||||||
|
@ -665,7 +733,6 @@ static void osdDrawElements(void)
|
||||||
osdDrawSingleElement(OSD_PITCH_ANGLE);
|
osdDrawSingleElement(OSD_PITCH_ANGLE);
|
||||||
osdDrawSingleElement(OSD_ROLL_ANGLE);
|
osdDrawSingleElement(OSD_ROLL_ANGLE);
|
||||||
osdDrawSingleElement(OSD_MAIN_BATT_USAGE);
|
osdDrawSingleElement(OSD_MAIN_BATT_USAGE);
|
||||||
osdDrawSingleElement(OSD_ARMED_TIME);
|
|
||||||
osdDrawSingleElement(OSD_DISARMED);
|
osdDrawSingleElement(OSD_DISARMED);
|
||||||
osdDrawSingleElement(OSD_NUMERICAL_HEADING);
|
osdDrawSingleElement(OSD_NUMERICAL_HEADING);
|
||||||
osdDrawSingleElement(OSD_NUMERICAL_VARIO);
|
osdDrawSingleElement(OSD_NUMERICAL_VARIO);
|
||||||
|
@ -697,8 +764,8 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
||||||
osdConfig->item_pos[OSD_CROSSHAIRS] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_CROSSHAIRS] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_ONTIME] = OSD_POS(22, 1) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_ITEM_TIMER_1] = OSD_POS(22, 1) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_FLYTIME] = OSD_POS(1, 1) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(1, 1) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_FLYMODE] = OSD_POS(13, 10) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_FLYMODE] = OSD_POS(13, 10) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_CRAFT_NAME] = OSD_POS(10, 11) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_CRAFT_NAME] = OSD_POS(10, 11) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_THROTTLE_POS] = OSD_POS(1, 7) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_THROTTLE_POS] = OSD_POS(1, 7) | VISIBLE_FLAG;
|
||||||
|
@ -724,7 +791,6 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
||||||
osdConfig->item_pos[OSD_HOME_DIR] = OSD_POS(14, 9) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_HOME_DIR] = OSD_POS(14, 9) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_COMPASS_BAR] = OSD_POS(10, 8) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_COMPASS_BAR] = OSD_POS(10, 8) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_MAIN_BATT_USAGE] = OSD_POS(8, 12) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_MAIN_BATT_USAGE] = OSD_POS(8, 12) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_ARMED_TIME] = OSD_POS(1, 2) | VISIBLE_FLAG;
|
|
||||||
osdConfig->item_pos[OSD_DISARMED] = OSD_POS(10, 4) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_DISARMED] = OSD_POS(10, 4) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_NUMERICAL_HEADING] = OSD_POS(23, 9) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_NUMERICAL_HEADING] = OSD_POS(23, 9) | VISIBLE_FLAG;
|
||||||
osdConfig->item_pos[OSD_NUMERICAL_VARIO] = OSD_POS(23, 8) | VISIBLE_FLAG;
|
osdConfig->item_pos[OSD_NUMERICAL_VARIO] = OSD_POS(23, 8) | VISIBLE_FLAG;
|
||||||
|
@ -739,16 +805,18 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
||||||
osdConfig->enabled_stats[OSD_STAT_MAX_ALTITUDE] = false;
|
osdConfig->enabled_stats[OSD_STAT_MAX_ALTITUDE] = false;
|
||||||
osdConfig->enabled_stats[OSD_STAT_BLACKBOX] = true;
|
osdConfig->enabled_stats[OSD_STAT_BLACKBOX] = true;
|
||||||
osdConfig->enabled_stats[OSD_STAT_END_BATTERY] = false;
|
osdConfig->enabled_stats[OSD_STAT_END_BATTERY] = false;
|
||||||
osdConfig->enabled_stats[OSD_STAT_FLYTIME] = false;
|
|
||||||
osdConfig->enabled_stats[OSD_STAT_ARMEDTIME] = true;
|
|
||||||
osdConfig->enabled_stats[OSD_STAT_MAX_DISTANCE] = false;
|
osdConfig->enabled_stats[OSD_STAT_MAX_DISTANCE] = false;
|
||||||
osdConfig->enabled_stats[OSD_STAT_BLACKBOX_NUMBER] = true;
|
osdConfig->enabled_stats[OSD_STAT_BLACKBOX_NUMBER] = true;
|
||||||
|
osdConfig->enabled_stats[OSD_STAT_TIMER_1] = false;
|
||||||
|
osdConfig->enabled_stats[OSD_STAT_TIMER_2] = true;
|
||||||
|
|
||||||
osdConfig->units = OSD_UNIT_METRIC;
|
osdConfig->units = OSD_UNIT_METRIC;
|
||||||
|
|
||||||
|
osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10);
|
||||||
|
osdConfig->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10);
|
||||||
|
|
||||||
osdConfig->rssi_alarm = 20;
|
osdConfig->rssi_alarm = 20;
|
||||||
osdConfig->cap_alarm = 2200;
|
osdConfig->cap_alarm = 2200;
|
||||||
osdConfig->time_alarm = 10; // in minutes
|
|
||||||
osdConfig->alt_alarm = 100; // meters or feet depend on configuration
|
osdConfig->alt_alarm = 100; // meters or feet depend on configuration
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -824,10 +892,15 @@ void osdUpdateAlarms(void)
|
||||||
else
|
else
|
||||||
CLR_BLINK(OSD_GPS_SATS);
|
CLR_BLINK(OSD_GPS_SATS);
|
||||||
|
|
||||||
if (flyTime / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED))
|
for (int i = 0; i < OSD_TIMER_COUNT; i++) {
|
||||||
SET_BLINK(OSD_FLYTIME);
|
const uint16_t timer = osdConfig()->timers[i];
|
||||||
|
const timeUs_t time = osdGetTimerValue(OSD_TIMER_SRC(timer));
|
||||||
|
const timeUs_t alarmTime = OSD_TIMER_ALARM(timer) * 60000000; // convert from minutes to us
|
||||||
|
if (alarmTime != 0 && time >= alarmTime)
|
||||||
|
SET_BLINK(OSD_ITEM_TIMER_1 + i);
|
||||||
else
|
else
|
||||||
CLR_BLINK(OSD_FLYTIME);
|
CLR_BLINK(OSD_ITEM_TIMER_1 + i);
|
||||||
|
}
|
||||||
|
|
||||||
if (getMAhDrawn() >= osdConfig()->cap_alarm) {
|
if (getMAhDrawn() >= osdConfig()->cap_alarm) {
|
||||||
SET_BLINK(OSD_MAH_DRAWN);
|
SET_BLINK(OSD_MAH_DRAWN);
|
||||||
|
@ -849,11 +922,12 @@ void osdResetAlarms(void)
|
||||||
CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
|
CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
|
||||||
CLR_BLINK(OSD_WARNINGS);
|
CLR_BLINK(OSD_WARNINGS);
|
||||||
CLR_BLINK(OSD_GPS_SATS);
|
CLR_BLINK(OSD_GPS_SATS);
|
||||||
CLR_BLINK(OSD_FLYTIME);
|
|
||||||
CLR_BLINK(OSD_MAH_DRAWN);
|
CLR_BLINK(OSD_MAH_DRAWN);
|
||||||
CLR_BLINK(OSD_ALTITUDE);
|
CLR_BLINK(OSD_ALTITUDE);
|
||||||
CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
|
CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
|
||||||
CLR_BLINK(OSD_MAIN_BATT_USAGE);
|
CLR_BLINK(OSD_MAIN_BATT_USAGE);
|
||||||
|
CLR_BLINK(OSD_ITEM_TIMER_1);
|
||||||
|
CLR_BLINK(OSD_ITEM_TIMER_2);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void osdResetStats(void)
|
static void osdResetStats(void)
|
||||||
|
@ -954,14 +1028,14 @@ static void osdShowStats(void)
|
||||||
displayClearScreen(osdDisplayPort);
|
displayClearScreen(osdDisplayPort);
|
||||||
displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
|
displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
|
||||||
|
|
||||||
if (osdConfig()->enabled_stats[OSD_STAT_ARMEDTIME]) {
|
if (osdConfig()->enabled_stats[OSD_STAT_TIMER_1]) {
|
||||||
tfp_sprintf(buff, "%02d:%02d", stats.armed_time / 60, stats.armed_time % 60);
|
osdFormatTimer(buff, false, OSD_TIMER_1);
|
||||||
osdDisplayStatisticLabel(top++, "ARMED TIME", buff);
|
osdDisplayStatisticLabel(top++, osdTimerSourceNames[OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1])], buff);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (osdConfig()->enabled_stats[OSD_STAT_FLYTIME]) {
|
if (osdConfig()->enabled_stats[OSD_STAT_TIMER_2]) {
|
||||||
tfp_sprintf(buff, "%02d:%02d", flyTime / 60, flyTime % 60);
|
osdFormatTimer(buff, false, OSD_TIMER_2);
|
||||||
osdDisplayStatisticLabel(top++, "FLY TIME", buff);
|
osdDisplayStatisticLabel(top++, osdTimerSourceNames[OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_2])], buff);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (osdConfig()->enabled_stats[OSD_STAT_MAX_SPEED] && STATE(GPS_FIX)) {
|
if (osdConfig()->enabled_stats[OSD_STAT_MAX_SPEED] && STATE(GPS_FIX)) {
|
||||||
|
@ -1033,8 +1107,7 @@ static void osdShowArmed(void)
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
|
STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
static uint8_t lastSec = 0;
|
static timeUs_t lastTimeUs = 0;
|
||||||
uint8_t sec;
|
|
||||||
|
|
||||||
// detect arm/disarm
|
// detect arm/disarm
|
||||||
if (armState != ARMING_FLAG(ARMED)) {
|
if (armState != ARMING_FLAG(ARMED)) {
|
||||||
|
@ -1054,13 +1127,12 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
osdUpdateStats();
|
osdUpdateStats();
|
||||||
|
|
||||||
sec = currentTimeUs / 1000000;
|
if (ARMING_FLAG(ARMED)) {
|
||||||
|
timeUs_t deltaT = currentTimeUs - lastTimeUs;
|
||||||
if (ARMING_FLAG(ARMED) && sec != lastSec) {
|
flyTime += deltaT;
|
||||||
flyTime++;
|
stats.armed_time += deltaT;
|
||||||
stats.armed_time++;
|
|
||||||
lastSec = sec;
|
|
||||||
}
|
}
|
||||||
|
lastTimeUs = currentTimeUs;
|
||||||
|
|
||||||
if (resumeRefreshAt) {
|
if (resumeRefreshAt) {
|
||||||
if (cmp32(currentTimeUs, resumeRefreshAt) < 0) {
|
if (cmp32(currentTimeUs, resumeRefreshAt) < 0) {
|
||||||
|
|
|
@ -21,27 +21,38 @@
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
|
#define OSD_NUM_TIMER_TYPES 3
|
||||||
|
extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
|
||||||
|
|
||||||
|
#define OSD_ELEMENT_BUFFER_LENGTH 32
|
||||||
|
|
||||||
#define VISIBLE_FLAG 0x0800
|
#define VISIBLE_FLAG 0x0800
|
||||||
#define VISIBLE(x) (x & VISIBLE_FLAG)
|
#define VISIBLE(x) (x & VISIBLE_FLAG)
|
||||||
#define OSD_POS_MAX 0x3FF
|
#define OSD_POS_MAX 0x3FF
|
||||||
#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x3FF) // For CLI values
|
#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x3FF) // For CLI values
|
||||||
|
|
||||||
// Character coordinate
|
// Character coordinate
|
||||||
|
|
||||||
#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
|
#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
|
||||||
#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
|
#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
|
||||||
#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
|
#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
|
||||||
#define OSD_X(x) (x & OSD_POSITION_XY_MASK)
|
#define OSD_X(x) (x & OSD_POSITION_XY_MASK)
|
||||||
#define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
|
#define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
|
||||||
|
|
||||||
|
// Timer configuration
|
||||||
|
// Stored as 15[alarm:8][precision:4][source:4]0
|
||||||
|
#define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8))
|
||||||
|
#define OSD_TIMER_SRC(timer) (timer & 0x0F)
|
||||||
|
#define OSD_TIMER_PRECISION(timer) ((timer >> 4) & 0x0F)
|
||||||
|
#define OSD_TIMER_ALARM(timer) ((timer >> 8) & 0xFF)
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
OSD_RSSI_VALUE,
|
OSD_RSSI_VALUE,
|
||||||
OSD_MAIN_BATT_VOLTAGE,
|
OSD_MAIN_BATT_VOLTAGE,
|
||||||
OSD_CROSSHAIRS,
|
OSD_CROSSHAIRS,
|
||||||
OSD_ARTIFICIAL_HORIZON,
|
OSD_ARTIFICIAL_HORIZON,
|
||||||
OSD_HORIZON_SIDEBARS,
|
OSD_HORIZON_SIDEBARS,
|
||||||
OSD_ONTIME,
|
OSD_ITEM_TIMER_1,
|
||||||
OSD_FLYTIME,
|
OSD_ITEM_TIMER_2,
|
||||||
OSD_FLYMODE,
|
OSD_FLYMODE,
|
||||||
OSD_CRAFT_NAME,
|
OSD_CRAFT_NAME,
|
||||||
OSD_THROTTLE_POS,
|
OSD_THROTTLE_POS,
|
||||||
|
@ -64,7 +75,6 @@ typedef enum {
|
||||||
OSD_PITCH_ANGLE,
|
OSD_PITCH_ANGLE,
|
||||||
OSD_ROLL_ANGLE,
|
OSD_ROLL_ANGLE,
|
||||||
OSD_MAIN_BATT_USAGE,
|
OSD_MAIN_BATT_USAGE,
|
||||||
OSD_ARMED_TIME,
|
|
||||||
OSD_DISARMED,
|
OSD_DISARMED,
|
||||||
OSD_HOME_DIR,
|
OSD_HOME_DIR,
|
||||||
OSD_HOME_DIST,
|
OSD_HOME_DIST,
|
||||||
|
@ -85,8 +95,8 @@ typedef enum {
|
||||||
OSD_STAT_MAX_ALTITUDE,
|
OSD_STAT_MAX_ALTITUDE,
|
||||||
OSD_STAT_BLACKBOX,
|
OSD_STAT_BLACKBOX,
|
||||||
OSD_STAT_END_BATTERY,
|
OSD_STAT_END_BATTERY,
|
||||||
OSD_STAT_FLYTIME,
|
OSD_STAT_TIMER_1,
|
||||||
OSD_STAT_ARMEDTIME,
|
OSD_STAT_TIMER_2,
|
||||||
OSD_STAT_MAX_DISTANCE,
|
OSD_STAT_MAX_DISTANCE,
|
||||||
OSD_STAT_BLACKBOX_NUMBER,
|
OSD_STAT_BLACKBOX_NUMBER,
|
||||||
OSD_STAT_COUNT // MUST BE LAST
|
OSD_STAT_COUNT // MUST BE LAST
|
||||||
|
@ -97,6 +107,25 @@ typedef enum {
|
||||||
OSD_UNIT_METRIC
|
OSD_UNIT_METRIC
|
||||||
} osd_unit_e;
|
} osd_unit_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
OSD_TIMER_1,
|
||||||
|
OSD_TIMER_2,
|
||||||
|
OSD_TIMER_COUNT
|
||||||
|
} osd_timer_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
OSD_TIMER_SRC_ON,
|
||||||
|
OSD_TIMER_SRC_TOTAL_ARMED,
|
||||||
|
OSD_TIMER_SRC_LAST_ARMED,
|
||||||
|
OSD_TIMER_SRC_COUNT
|
||||||
|
} osd_timer_source_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
OSD_TIMER_PREC_SECOND,
|
||||||
|
OSD_TIMER_PREC_HUNDREDTHS,
|
||||||
|
OSD_TIMER_PREC_COUNT
|
||||||
|
} osd_timer_precision_e;
|
||||||
|
|
||||||
typedef struct osdConfig_s {
|
typedef struct osdConfig_s {
|
||||||
uint16_t item_pos[OSD_ITEM_COUNT];
|
uint16_t item_pos[OSD_ITEM_COUNT];
|
||||||
bool enabled_stats[OSD_STAT_COUNT];
|
bool enabled_stats[OSD_STAT_COUNT];
|
||||||
|
@ -104,10 +133,11 @@ typedef struct osdConfig_s {
|
||||||
// Alarms
|
// Alarms
|
||||||
uint8_t rssi_alarm;
|
uint8_t rssi_alarm;
|
||||||
uint16_t cap_alarm;
|
uint16_t cap_alarm;
|
||||||
uint16_t time_alarm;
|
|
||||||
uint16_t alt_alarm;
|
uint16_t alt_alarm;
|
||||||
|
|
||||||
osd_unit_e units;
|
osd_unit_e units;
|
||||||
|
|
||||||
|
uint16_t timers[OSD_TIMER_COUNT];
|
||||||
} osdConfig_t;
|
} osdConfig_t;
|
||||||
|
|
||||||
extern uint32_t resumeRefreshAt;
|
extern uint32_t resumeRefreshAt;
|
||||||
|
|
|
@ -311,7 +311,7 @@ uint8_t BL_PageErase(ioMem_t *pMem)
|
||||||
if (BL_SendCMDSetAddress(pMem)) {
|
if (BL_SendCMDSetAddress(pMem)) {
|
||||||
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
|
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
|
||||||
BL_SendBuf(sCMD, 2);
|
BL_SendBuf(sCMD, 2);
|
||||||
return (BL_GetACK((1000 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
|
return (BL_GetACK((1400 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -323,7 +323,7 @@ uint8_t BL_WriteEEprom(ioMem_t *pMem)
|
||||||
|
|
||||||
uint8_t BL_WriteFlash(ioMem_t *pMem)
|
uint8_t BL_WriteFlash(ioMem_t *pMem)
|
||||||
{
|
{
|
||||||
return BL_WriteA(CMD_PROG_FLASH, pMem, (40 / START_BIT_TIMEOUT_MS));
|
return BL_WriteA(CMD_PROG_FLASH, pMem, (500 / START_BIT_TIMEOUT_MS));
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t BL_VerifyFlash(ioMem_t *pMem)
|
uint8_t BL_VerifyFlash(ioMem_t *pMem)
|
||||||
|
|
|
@ -81,7 +81,7 @@ static uint32_t needRxSignalMaxDelayUs;
|
||||||
static uint32_t suspendRxSignalUntil = 0;
|
static uint32_t suspendRxSignalUntil = 0;
|
||||||
static uint8_t skipRxSamples = 0;
|
static uint8_t skipRxSamples = 0;
|
||||||
|
|
||||||
int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
static int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||||
|
|
||||||
|
@ -516,7 +516,7 @@ static void readRxChannelsApplyRanges(void)
|
||||||
const int channelCount = getRxChannelCount();
|
const int channelCount = getRxChannelCount();
|
||||||
for (int channel = 0; channel < channelCount; channel++) {
|
for (int channel = 0; channel < channelCount; channel++) {
|
||||||
|
|
||||||
const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);
|
const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, RX_MAPPABLE_CHANNEL_COUNT, channel);
|
||||||
|
|
||||||
// sample the channel
|
// sample the channel
|
||||||
uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel);
|
uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel);
|
||||||
|
@ -617,7 +617,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
for (const char *c = input; *c; c++) {
|
for (const char *c = input; *c; c++) {
|
||||||
const char *s = strchr(rcChannelLetters, *c);
|
const char *s = strchr(rcChannelLetters, *c);
|
||||||
if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS)) {
|
if (s && (s < rcChannelLetters + RX_MAPPABLE_CHANNEL_COUNT)) {
|
||||||
rxConfig->rcmap[s - rcChannelLetters] = c - input;
|
rxConfig->rcmap[s - rcChannelLetters] = c - input;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -78,7 +78,7 @@ extern const char rcChannelLetters[];
|
||||||
|
|
||||||
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
|
|
||||||
#define MAX_MAPPABLE_RX_INPUTS 8
|
#define RX_MAPPABLE_CHANNEL_COUNT 8
|
||||||
|
|
||||||
#define RSSI_SCALE_MIN 1
|
#define RSSI_SCALE_MIN 1
|
||||||
#define RSSI_SCALE_MAX 255
|
#define RSSI_SCALE_MAX 255
|
||||||
|
@ -115,7 +115,7 @@ typedef struct rxChannelRangeConfig_s {
|
||||||
PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
|
PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
|
||||||
|
|
||||||
typedef struct rxConfig_s {
|
typedef struct rxConfig_s {
|
||||||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
|
||||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||||
uint8_t sbus_inversion; // default sbus (Futaba, FrSKY) is inverted. Support for uninverted OpenLRS (and modified FrSKY) receivers.
|
uint8_t sbus_inversion; // default sbus (Futaba, FrSKY) is inverted. Support for uninverted OpenLRS (and modified FrSKY) receivers.
|
||||||
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
||||||
|
@ -145,8 +145,6 @@ typedef struct rxConfig_s {
|
||||||
|
|
||||||
PG_DECLARE(rxConfig_t, rxConfig);
|
PG_DECLARE(rxConfig_t, rxConfig);
|
||||||
|
|
||||||
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
|
|
||||||
|
|
||||||
struct rxRuntimeConfig_s;
|
struct rxRuntimeConfig_s;
|
||||||
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
|
||||||
typedef uint8_t (*rcFrameStatusFnPtr)(void);
|
typedef uint8_t (*rcFrameStatusFnPtr)(void);
|
||||||
|
|
|
@ -77,6 +77,8 @@ typedef struct gyroCalibration_s {
|
||||||
uint16_t calibratingG;
|
uint16_t calibratingG;
|
||||||
} gyroCalibration_t;
|
} gyroCalibration_t;
|
||||||
|
|
||||||
|
bool firstArmingCalibrationWasStarted = false;
|
||||||
|
|
||||||
typedef union gyroSoftFilter_u {
|
typedef union gyroSoftFilter_u {
|
||||||
biquadFilter_t gyroFilterLpfState[XYZ_AXIS_COUNT];
|
biquadFilter_t gyroFilterLpfState[XYZ_AXIS_COUNT];
|
||||||
pt1Filter_t gyroFilterPt1State[XYZ_AXIS_COUNT];
|
pt1Filter_t gyroFilterPt1State[XYZ_AXIS_COUNT];
|
||||||
|
@ -489,9 +491,20 @@ static void gyroSetCalibrationCycles(gyroSensor_t *gyroSensor)
|
||||||
gyroSensor->calibration.calibratingG = gyroCalculateCalibratingCycles();
|
gyroSensor->calibration.calibratingG = gyroCalculateCalibratingCycles();
|
||||||
}
|
}
|
||||||
|
|
||||||
void gyroStartCalibration(void)
|
void gyroStartCalibration(bool isFirstArmingCalibration)
|
||||||
{
|
{
|
||||||
|
if (!(isFirstArmingCalibration && firstArmingCalibrationWasStarted)) {
|
||||||
gyroSetCalibrationCycles(&gyroSensor0);
|
gyroSetCalibrationCycles(&gyroSensor0);
|
||||||
|
|
||||||
|
if (isFirstArmingCalibration) {
|
||||||
|
firstArmingCalibrationWasStarted = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool isFirstArmingGyroCalibrationRunning(void)
|
||||||
|
{
|
||||||
|
return firstArmingCalibrationWasStarted && !isGyroCalibrationComplete();
|
||||||
}
|
}
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t gyroMovementCalibrationThreshold)
|
STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t gyroMovementCalibrationThreshold)
|
||||||
|
@ -525,8 +538,10 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t
|
||||||
|
|
||||||
if (isOnFinalGyroCalibrationCycle(&gyroSensor->calibration)) {
|
if (isOnFinalGyroCalibrationCycle(&gyroSensor->calibration)) {
|
||||||
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
|
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
|
||||||
|
if (!firstArmingCalibrationWasStarted || !isArmingDisabled()) {
|
||||||
beeper(BEEPER_GYRO_CALIBRATED);
|
beeper(BEEPER_GYRO_CALIBRATED);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
--gyroSensor->calibration.calibratingG;
|
--gyroSensor->calibration.calibratingG;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -74,7 +74,8 @@ struct mpuConfiguration_s;
|
||||||
const struct mpuConfiguration_s *gyroMpuConfiguration(void);
|
const struct mpuConfiguration_s *gyroMpuConfiguration(void);
|
||||||
struct mpuDetectionResult_s;
|
struct mpuDetectionResult_s;
|
||||||
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
|
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
|
||||||
void gyroStartCalibration(void);
|
void gyroStartCalibration(bool isFirstArmingCalibration);
|
||||||
|
bool isFirstArmingGyroCalibrationRunning(void);
|
||||||
bool isGyroCalibrationComplete(void);
|
bool isGyroCalibrationComplete(void);
|
||||||
void gyroReadTemperature(void);
|
void gyroReadTemperature(void);
|
||||||
int16_t gyroGetTemperature(void);
|
int16_t gyroGetTemperature(void);
|
||||||
|
|
|
@ -87,6 +87,14 @@ Reset_Handler:
|
||||||
cmp r2, r1 // mj666
|
cmp r2, r1 // mj666
|
||||||
beq Reboot_Loader // mj666
|
beq Reboot_Loader // mj666
|
||||||
|
|
||||||
|
// Check for overclocking request
|
||||||
|
ldr r0, =0x2001FFF8 // Faduf
|
||||||
|
ldr r1, =0xBABEFACE // Faduf
|
||||||
|
ldr r2, [r0, #0] // Faduf
|
||||||
|
str r0, [r0, #0] // Faduf
|
||||||
|
cmp r2, r1 // Faduf
|
||||||
|
beq Boot_OC // Faduf
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
b LoopCopyDataInit
|
b LoopCopyDataInit
|
||||||
|
@ -135,6 +143,7 @@ LoopMarkHeapStack:
|
||||||
str r1,[r0]
|
str r1,[r0]
|
||||||
|
|
||||||
/* Call the clock system intitialization function.*/
|
/* Call the clock system intitialization function.*/
|
||||||
|
/* Done in system_stm32f4xx.c */
|
||||||
bl SystemInit
|
bl SystemInit
|
||||||
|
|
||||||
/* Call the application's entry point.*/
|
/* Call the application's entry point.*/
|
||||||
|
@ -144,6 +153,63 @@ LoopMarkHeapStack:
|
||||||
LoopForever:
|
LoopForever:
|
||||||
b LoopForever
|
b LoopForever
|
||||||
|
|
||||||
|
Boot_OC:
|
||||||
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
|
movs r1, #0
|
||||||
|
b LoopCopyDataInitOC
|
||||||
|
|
||||||
|
CopyDataInitOC:
|
||||||
|
ldr r3, =_sidata
|
||||||
|
ldr r3, [r3, r1]
|
||||||
|
str r3, [r0, r1]
|
||||||
|
adds r1, r1, #4
|
||||||
|
|
||||||
|
LoopCopyDataInitOC:
|
||||||
|
ldr r0, =_sdata
|
||||||
|
ldr r3, =_edata
|
||||||
|
adds r2, r0, r1
|
||||||
|
cmp r2, r3
|
||||||
|
bcc CopyDataInitOC
|
||||||
|
ldr r2, =_sbss
|
||||||
|
b LoopFillZerobssOC
|
||||||
|
/* Zero fill the bss segment. */
|
||||||
|
FillZerobssOC:
|
||||||
|
movs r3, #0
|
||||||
|
str r3, [r2], #4
|
||||||
|
|
||||||
|
LoopFillZerobssOC:
|
||||||
|
ldr r3, = _ebss
|
||||||
|
cmp r2, r3
|
||||||
|
bcc FillZerobssOC
|
||||||
|
|
||||||
|
/* Mark the heap and stack */
|
||||||
|
ldr r2, =_heap_stack_begin
|
||||||
|
b LoopMarkHeapStackOC
|
||||||
|
|
||||||
|
MarkHeapStackOC:
|
||||||
|
movs r3, 0xa5a5a5a5
|
||||||
|
str r3, [r2], #4
|
||||||
|
|
||||||
|
LoopMarkHeapStackOC:
|
||||||
|
ldr r3, = _heap_stack_end
|
||||||
|
cmp r2, r3
|
||||||
|
bcc MarkHeapStackOC
|
||||||
|
|
||||||
|
/*FPU settings*/
|
||||||
|
ldr r0, =0xE000ED88 /* Enable CP10,CP11 */
|
||||||
|
ldr r1,[r0]
|
||||||
|
orr r1,r1,#(0xF << 20)
|
||||||
|
str r1,[r0]
|
||||||
|
|
||||||
|
/* Call the clock system intitialization function.*/
|
||||||
|
/* Done in system_stm32f4xx.c */
|
||||||
|
bl SystemInitOC
|
||||||
|
|
||||||
|
/* Call the application's entry point.*/
|
||||||
|
bl main
|
||||||
|
bx lr
|
||||||
|
|
||||||
|
|
||||||
Reboot_Loader: // mj666
|
Reboot_Loader: // mj666
|
||||||
|
|
||||||
// Reboot to ROM // mj666
|
// Reboot to ROM // mj666
|
||||||
|
|
|
@ -95,7 +95,7 @@ void targetConfiguration(void)
|
||||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||||
rxConfigMutable()->sbus_inversion = 0;
|
rxConfigMutable()->sbus_inversion = 0;
|
||||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||||
telemetryConfigMutable()->telemetry_inverted = true;
|
telemetryConfigMutable()->telemetry_inverted = false;
|
||||||
featureSet(FEATURE_TELEMETRY);
|
featureSet(FEATURE_TELEMETRY);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -65,7 +65,7 @@ void targetConfiguration(void)
|
||||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||||
rxConfigMutable()->sbus_inversion = 0;
|
rxConfigMutable()->sbus_inversion = 0;
|
||||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||||
telemetryConfigMutable()->telemetry_inverted = true;
|
telemetryConfigMutable()->telemetry_inverted = false;
|
||||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||||
featureSet(FEATURE_TELEMETRY);
|
featureSet(FEATURE_TELEMETRY);
|
||||||
|
|
|
@ -64,7 +64,7 @@
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
|
|
||||||
//#define SDCARD_DETECT_INVERTED
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SDCARD_DETECT_PIN PB11
|
#define SDCARD_DETECT_PIN PB11
|
||||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
|
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
|
||||||
|
@ -88,11 +88,11 @@
|
||||||
// Performance logging for SD card operations:
|
// Performance logging for SD card operations:
|
||||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||||
|
|
||||||
//#define M25P16_CS_PIN SPI2_NSS_PIN
|
#define M25P16_CS_PIN SPI2_NSS_PIN
|
||||||
//#define M25P16_SPI_INSTANCE SPI2
|
#define M25P16_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
//#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
//#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
F405_TARGETS += $(TARGET)
|
F405_TARGETS += $(TARGET)
|
||||||
FEATURES += SDCARD VCP
|
FEATURES += SDCARD VCP ONBOARDFLASH
|
||||||
|
|
||||||
TARGET_SRC = \
|
TARGET_SRC = \
|
||||||
drivers/accgyro/accgyro_mpu6500.c \
|
drivers/accgyro/accgyro_mpu6500.c \
|
||||||
|
|
|
@ -64,7 +64,7 @@ void targetConfiguration(void)
|
||||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||||
rxConfigMutable()->sbus_inversion = 0;
|
rxConfigMutable()->sbus_inversion = 0;
|
||||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIALRX_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY | FUNCTION_RX_SERIAL;
|
||||||
telemetryConfigMutable()->telemetry_inverted = true;
|
telemetryConfigMutable()->telemetry_inverted = false;
|
||||||
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_ADC;
|
||||||
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
batteryConfigMutable()->currentMeterSource = CURRENT_METER_ADC;
|
||||||
featureSet(FEATURE_TELEMETRY);
|
featureSet(FEATURE_TELEMETRY);
|
||||||
|
|
|
@ -74,7 +74,7 @@
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
|
|
||||||
//#define SDCARD_DETECT_INVERTED
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SDCARD_DETECT_PIN PB11
|
#define SDCARD_DETECT_PIN PB11
|
||||||
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
|
#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
|
||||||
|
@ -86,9 +86,9 @@
|
||||||
#define SDCARD_SPI_CS_PIN PB10
|
#define SDCARD_SPI_CS_PIN PB10
|
||||||
|
|
||||||
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||||
// Divide to under 25MHz for normal operation:
|
// Divide to under 25MHz for normal operation:
|
||||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||||
|
|
||||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||||
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
|
||||||
|
@ -98,11 +98,11 @@
|
||||||
// Performance logging for SD card operations:
|
// Performance logging for SD card operations:
|
||||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||||
|
|
||||||
//#define M25P16_CS_PIN SPI2_NSS_PIN
|
#define M25P16_CS_PIN SPI2_NSS_PIN
|
||||||
//#define M25P16_SPI_INSTANCE SPI2
|
#define M25P16_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
//#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
//#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
||||||
|
@ -127,8 +127,8 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 6
|
#define SERIAL_PORT_COUNT 6
|
||||||
|
|
||||||
//#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PA8 // (HARDARE=0,PPM)
|
#define ESCSERIAL_TIMER_TX_PIN PA8 // (Hardware=0, PPM/LED_STRIP) XXX Crash if using an LED strip.
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
F7X2RE_TARGETS += $(TARGET)
|
F7X2RE_TARGETS += $(TARGET)
|
||||||
FEATURES += SDCARD VCP
|
FEATURES += SDCARD VCP ONBOARDFLASH
|
||||||
|
|
||||||
TARGET_SRC = \
|
TARGET_SRC = \
|
||||||
drivers/accgyro/accgyro_mpu6500.c \
|
drivers/accgyro/accgyro_mpu6500.c \
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "AnyFCF7"
|
#define USBD_PRODUCT_STRING "AnyFCF7"
|
||||||
|
|
||||||
#define LED0 PB7
|
#define LED0_PIN PB7
|
||||||
#define LED1 PB6
|
#define LED1_PIN PB6
|
||||||
|
|
||||||
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
@ -94,6 +94,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 11 //VCP, USART1, USART2, USART3, UART4, UART5, USART6, USART7, USART8, SOFTSERIAL x 2
|
#define SERIAL_PORT_COUNT 11 //VCP, USART1, USART2, USART3, UART4, UART5, USART6, USART7, USART8, SOFTSERIAL x 2
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PB14 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_4
|
#define USE_SPI_DEVICE_4
|
||||||
|
|
|
@ -23,8 +23,8 @@
|
||||||
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED0 PB6 //red
|
#define LED0_PIN PB6 //red
|
||||||
#define LED1 PB9 //blue
|
#define LED1_PIN PB9 //blue
|
||||||
|
|
||||||
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
#define BEEPER PB2 // Unused pin, can be mapped to elsewhere
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
@ -88,6 +88,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 7 //VCP, USART1, UART4, UART5, USART6, SOFTSERIAL x 2
|
#define SERIAL_PORT_COUNT 7 //VCP, USART1, UART4, UART5, USART6, SOFTSERIAL x 2
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PB14 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
37
src/main/target/BETAFLIGHTF4/target.c
Executable file
37
src/main/target/BETAFLIGHTF4/target.c
Executable file
|
@ -0,0 +1,37 @@
|
||||||
|
/*
|
||||||
|
* 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 <stdint.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
#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(TIM4, CH3, PB8, TIM_USE_PWM | TIM_USE_PPM, TIMER_OUTPUT_NONE, 0), // PPM
|
||||||
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S1_OUT D1_ST7
|
||||||
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S2_OUT D1_ST2
|
||||||
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S3_OUT D1_ST6
|
||||||
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S4_OUT D1_ST1
|
||||||
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
|
||||||
|
DEF_TIM(TIM3, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S6_OUT D1_ST2
|
||||||
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // LED
|
||||||
|
};
|
144
src/main/target/BETAFLIGHTF4/target.h
Executable file
144
src/main/target/BETAFLIGHTF4/target.h
Executable file
|
@ -0,0 +1,144 @@
|
||||||
|
/*
|
||||||
|
* 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 TARGET_BOARD_IDENTIFIER "BFF4"
|
||||||
|
#define USBD_PRODUCT_STRING "BetaFlightF4"
|
||||||
|
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
|
#define LED0_PIN PB5
|
||||||
|
|
||||||
|
// Leave beeper here but with none as io - so disabled unless mapped.
|
||||||
|
#define BEEPER PB4
|
||||||
|
|
||||||
|
// PC0 used as inverter select GPIO
|
||||||
|
#define INVERTER_PIN_UART6 PC13
|
||||||
|
|
||||||
|
#define MPU6000_CS_PIN PA4
|
||||||
|
#define MPU6000_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
|
#define ACC
|
||||||
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// MPU6000 interrupts
|
||||||
|
#define USE_EXTI
|
||||||
|
#define MPU_INT_EXTI PC4
|
||||||
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
|
#define BARO
|
||||||
|
#define USE_BARO_SPI_BMP280
|
||||||
|
|
||||||
|
#define BMP280_SPI_INSTANCE SPI2
|
||||||
|
#define BMP280_CS_PIN PB3
|
||||||
|
|
||||||
|
#define OSD
|
||||||
|
#define USE_MAX7456
|
||||||
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
|
#define MAX7456_SPI_CS_PIN PB12
|
||||||
|
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
|
||||||
|
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||||
|
|
||||||
|
#define M25P16_CS_PIN PA15
|
||||||
|
#define M25P16_SPI_INSTANCE SPI3
|
||||||
|
|
||||||
|
#define USE_FLASHFS
|
||||||
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define VBUS_SENSING_PIN PC5
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_UART1
|
||||||
|
#define UART1_RX_PIN PA10
|
||||||
|
#define UART1_TX_PIN PA9
|
||||||
|
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||||
|
|
||||||
|
#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_UART6
|
||||||
|
#define UART6_RX_PIN PC7
|
||||||
|
#define UART6_TX_PIN PC6
|
||||||
|
|
||||||
|
#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, USART3, USART6
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_SPI
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_1
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_2
|
||||||
|
#define SPI2_NSS_PIN PB12
|
||||||
|
#define SPI2_SCK_PIN PB13
|
||||||
|
#define SPI2_MISO_PIN PB14
|
||||||
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_3
|
||||||
|
#define SPI3_NSS_PIN PA15
|
||||||
|
#define SPI3_SCK_PIN PC10
|
||||||
|
#define SPI3_MISO_PIN PC11
|
||||||
|
#define SPI3_MOSI_PIN PC12
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_ADC
|
||||||
|
#define CURRENT_METER_ADC_PIN PC1
|
||||||
|
#define VBAT_ADC_PIN PC2
|
||||||
|
|
||||||
|
#define LED_STRIP
|
||||||
|
|
||||||
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
|
||||||
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||||
|
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
|
||||||
|
|
||||||
|
|
||||||
|
#define SPEKTRUM_BIND
|
||||||
|
// USART3,
|
||||||
|
#define BIND_PIN PB11
|
||||||
|
|
||||||
|
#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 8
|
||||||
|
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
|
10
src/main/target/BETAFLIGHTF4/target.mk
Executable file
10
src/main/target/BETAFLIGHTF4/target.mk
Executable file
|
@ -0,0 +1,10 @@
|
||||||
|
|
||||||
|
F405_TARGETS += $(TARGET)
|
||||||
|
FEATURES += VCP ONBOARDFLASH
|
||||||
|
|
||||||
|
TARGET_SRC = \
|
||||||
|
drivers/accgyro/accgyro_mpu.c \
|
||||||
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
|
drivers/barometer/barometer_bmp280.c \
|
||||||
|
drivers/barometer/barometer_spi_bmp280.c \
|
||||||
|
drivers/max7456.c
|
|
@ -104,6 +104,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 5
|
#define SERIAL_PORT_COUNT 5
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PB8 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
// XXX To target maintainer: Bus device to configure must be specified.
|
// XXX To target maintainer: Bus device to configure must be specified.
|
||||||
//#define USE_I2C
|
//#define USE_I2C
|
||||||
|
|
||||||
|
|
|
@ -411,7 +411,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BST_RX_MAP:
|
case BST_RX_MAP:
|
||||||
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++)
|
for (i = 0; i < RX_MAPPABLE_CHANNEL_COUNT; i++)
|
||||||
bstWrite8(rxConfig()->rcmap[i]);
|
bstWrite8(rxConfig()->rcmap[i]);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -563,7 +563,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case BST_SET_RX_MAP:
|
case BST_SET_RX_MAP:
|
||||||
for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
|
for (i = 0; i < RX_MAPPABLE_CHANNEL_COUNT; i++) {
|
||||||
rxConfigMutable()->rcmap[i] = bstRead8();
|
rxConfigMutable()->rcmap[i] = bstRead8();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -118,6 +118,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART6, SOFTSERIAL x 2
|
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART6, SOFTSERIAL x 2
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PC9 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define USE_I2C_DEVICE_1
|
#define USE_I2C_DEVICE_1
|
||||||
#define I2C_DEVICE (I2CDEV_1)
|
#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
|
|
@ -94,8 +94,8 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 6
|
#define SERIAL_PORT_COUNT 6
|
||||||
|
|
||||||
//#define USE_ESCSERIAL //TODO: make ESC serial F7 compatible
|
#define USE_ESCSERIAL
|
||||||
//#define ESCSERIAL_TIMER_TX_PIN PC7 // (HARDARE=0,PPM)
|
#define ESCSERIAL_TIMER_TX_PIN PC7 // (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "NucleoF7"
|
#define USBD_PRODUCT_STRING "NucleoF7"
|
||||||
|
|
||||||
#define LED0 PB7
|
#define LED0_PIN PB7
|
||||||
#define LED1 PB14
|
#define LED1_PIN PB14
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
@ -93,6 +93,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 10 //VCP, USART2, USART3, UART4, UART5, USART6, USART7, USART8, SOFTSERIAL x 2
|
#define SERIAL_PORT_COUNT 10 //VCP, USART2, USART3, UART4, UART5, USART6, USART7, USART8, SOFTSERIAL x 2
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PPM
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PB15 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_4
|
#define USE_SPI_DEVICE_4
|
||||||
|
|
|
@ -23,8 +23,8 @@
|
||||||
|
|
||||||
//#define USE_ESC_TELEMETRY
|
//#define USE_ESC_TELEMETRY
|
||||||
|
|
||||||
#define LED0 PB7 // blue
|
#define LED0_PIN PB7 // blue
|
||||||
#define LED1 PB14 // red
|
#define LED1_PIN PB14 // red
|
||||||
|
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
@ -95,6 +95,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 6 //VCP, USART2, USART3, UART4,SOFTSERIAL x 2
|
#define SERIAL_PORT_COUNT 6 //VCP, USART2, USART3, UART4,SOFTSERIAL x 2
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PPM
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PB15 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_4
|
#define USE_SPI_DEVICE_4
|
||||||
|
|
|
@ -78,6 +78,10 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PPM
|
||||||
|
#define ESCSERIAL_TIMER_TX_PIN PE13 // XXX Provisional (Hardware=0, PPM)
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
|
@ -269,7 +269,7 @@ void failureMode(failureMode_e mode) {
|
||||||
while (1);
|
while (1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void failureLedCode(failureMode_e mode, int repeatCount)
|
void indicateFailure(failureMode_e mode, int repeatCount)
|
||||||
{
|
{
|
||||||
UNUSED(repeatCount);
|
UNUSED(repeatCount);
|
||||||
printf("Failure LED flash for: [failureMode]!!! %d\n", mode);
|
printf("Failure LED flash for: [failureMode]!!! %d\n", mode);
|
||||||
|
@ -374,7 +374,7 @@ int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y)
|
||||||
|
|
||||||
|
|
||||||
// PWM part
|
// PWM part
|
||||||
bool pwmMotorsEnabled = false;
|
static bool pwmMotorsEnabled = false;
|
||||||
static pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
static pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
||||||
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
||||||
|
|
||||||
|
@ -406,6 +406,10 @@ pwmOutputPort_t *pwmGetMotors(void) {
|
||||||
return motors;
|
return motors;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void pwmEnableMotors(void) {
|
||||||
|
pwmMotorsEnabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
bool pwmAreMotorsEnabled(void) {
|
bool pwmAreMotorsEnabled(void) {
|
||||||
return pwmMotorsEnabled;
|
return pwmMotorsEnabled;
|
||||||
}
|
}
|
||||||
|
|
|
@ -162,6 +162,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define OSD
|
#define OSD
|
||||||
|
#define DISABLE_EXTENDED_CMS_OSD_MENU
|
||||||
#define USE_OSD_OVER_MSP_DISPLAYPORT
|
#define USE_OSD_OVER_MSP_DISPLAYPORT
|
||||||
#define USE_MSP_CURRENT_METER
|
#define USE_MSP_CURRENT_METER
|
||||||
|
|
||||||
|
|
|
@ -21,8 +21,8 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "VRRACE"
|
#define USBD_PRODUCT_STRING "VRRACE"
|
||||||
|
|
||||||
#define LED0 PD14
|
#define LED0_PIN PD14
|
||||||
#define LED1 PD15
|
#define LED1_PIN PD15
|
||||||
#define BEEPER PA0
|
#define BEEPER PA0
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -160,6 +160,8 @@
|
||||||
#define USE_RTOS 0U
|
#define USE_RTOS 0U
|
||||||
#define PREFETCH_ENABLE 0U
|
#define PREFETCH_ENABLE 0U
|
||||||
#define ART_ACCLERATOR_ENABLE 0U /* To enable instruction cache and prefetch */
|
#define ART_ACCLERATOR_ENABLE 0U /* To enable instruction cache and prefetch */
|
||||||
|
#define INSTRUCTION_CACHE_ENABLE 1U
|
||||||
|
#define DATA_CACHE_ENABLE 0U
|
||||||
|
|
||||||
/* ########################## Assert Selection ############################## */
|
/* ########################## Assert Selection ############################## */
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -422,8 +422,6 @@ uint32_t hse_value = HSE_VALUE;
|
||||||
/** @addtogroup STM32F4xx_System_Private_Variables
|
/** @addtogroup STM32F4xx_System_Private_Variables
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
/* core clock is simply a mhz of PLL_N / PLL_P */
|
|
||||||
uint32_t SystemCoreClock = (PLL_N / PLL_P) * 1000000;
|
|
||||||
|
|
||||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||||
|
|
||||||
|
@ -456,8 +454,15 @@ static void SystemInit_ExtMemCtl(void);
|
||||||
* @param None
|
* @param None
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
uint32_t SystemCoreClock;
|
||||||
|
uint32_t pll_p = PLL_P, pll_n = PLL_N, pll_q = PLL_Q;
|
||||||
|
|
||||||
void SystemInit(void)
|
void SystemInit(void)
|
||||||
{
|
{
|
||||||
|
/* core clock is simply a mhz of PLL_N / PLL_P */
|
||||||
|
SystemCoreClock = (pll_n / pll_p) * 1000000;
|
||||||
|
|
||||||
/* FPU settings ------------------------------------------------------------*/
|
/* FPU settings ------------------------------------------------------------*/
|
||||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||||
|
@ -487,7 +492,7 @@ void SystemInit(void)
|
||||||
|
|
||||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||||
SetSysClock();
|
//SetSysClock();
|
||||||
|
|
||||||
/* Configure the Vector Table location add offset address ------------------*/
|
/* Configure the Vector Table location add offset address ------------------*/
|
||||||
#ifdef VECT_TAB_SRAM
|
#ifdef VECT_TAB_SRAM
|
||||||
|
@ -497,6 +502,16 @@ void SystemInit(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void SystemInitOC(void)
|
||||||
|
{
|
||||||
|
/* PLL setting for overclocking */
|
||||||
|
pll_n = PLL_N_OC;
|
||||||
|
pll_p = PLL_P_OC;
|
||||||
|
pll_q = PLL_Q_OC;
|
||||||
|
|
||||||
|
SystemInit();
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||||
|
@ -673,12 +688,12 @@ void SetSysClock(void)
|
||||||
|
|
||||||
#if defined(STM32F446xx)
|
#if defined(STM32F446xx)
|
||||||
/* Configure the main PLL */
|
/* Configure the main PLL */
|
||||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
RCC->PLLCFGR = PLL_M | (pll_n << 6) | (((pll_p >> 1) -1) << 16) |
|
||||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
|
(RCC_PLLCFGR_PLLSRC_HSE) | (pll_q << 24) | (PLL_R << 28);
|
||||||
#else
|
#else
|
||||||
/* Configure the main PLL */
|
/* Configure the main PLL */
|
||||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
RCC->PLLCFGR = PLL_M | (pll_n << 6) | (((pll_p >> 1) -1) << 16) |
|
||||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
|
(RCC_PLLCFGR_PLLSRC_HSE) | (pll_q << 24);
|
||||||
#endif /* STM32F446xx */
|
#endif /* STM32F446xx */
|
||||||
|
|
||||||
/* Enable the main PLL */
|
/* Enable the main PLL */
|
||||||
|
|
|
@ -32,8 +32,14 @@
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define PLL_N_OC 480
|
||||||
|
#define PLL_P_OC 2
|
||||||
|
#define PLL_Q_OC 10
|
||||||
|
#define OC_FREQUENCY_HZ (1000000*PLL_N_OC/PLL_P_OC)
|
||||||
|
|
||||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||||
extern void SystemInit(void);
|
extern void SystemInit(void);
|
||||||
|
extern void SystemInitOC(void);
|
||||||
extern void SystemCoreClockUpdate(void);
|
extern void SystemCoreClockUpdate(void);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
|
|
|
@ -167,16 +167,14 @@
|
||||||
RCC_OscInitStruct.PLL.PLLQ = PLL_Q;
|
RCC_OscInitStruct.PLL.PLLQ = PLL_Q;
|
||||||
|
|
||||||
ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
|
ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
|
||||||
if(ret != HAL_OK)
|
if (ret != HAL_OK) {
|
||||||
{
|
while (1);
|
||||||
while(1) { ; }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Activate the OverDrive to reach the 216 MHz Frequency */
|
/* Activate the OverDrive to reach the 216 MHz Frequency */
|
||||||
ret = HAL_PWREx_EnableOverDrive();
|
ret = HAL_PWREx_EnableOverDrive();
|
||||||
if(ret != HAL_OK)
|
if (ret != HAL_OK) {
|
||||||
{
|
while (1);
|
||||||
while(1) { ; }
|
|
||||||
}
|
}
|
||||||
/* Select PLLSAI output as USB clock source */
|
/* Select PLLSAI output as USB clock source */
|
||||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48;
|
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48;
|
||||||
|
@ -184,9 +182,8 @@
|
||||||
PeriphClkInitStruct.PLLSAI.PLLSAIN = PLL_SAIN;
|
PeriphClkInitStruct.PLLSAI.PLLSAIN = PLL_SAIN;
|
||||||
PeriphClkInitStruct.PLLSAI.PLLSAIQ = PLL_SAIQ;
|
PeriphClkInitStruct.PLLSAI.PLLSAIQ = PLL_SAIQ;
|
||||||
PeriphClkInitStruct.PLLSAI.PLLSAIP = PLL_SAIP;
|
PeriphClkInitStruct.PLLSAI.PLLSAIP = PLL_SAIP;
|
||||||
if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
|
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) {
|
||||||
{
|
while (1);
|
||||||
while(1) {};
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
|
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
|
||||||
|
@ -197,9 +194,8 @@
|
||||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
|
||||||
|
|
||||||
ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7);
|
ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7);
|
||||||
if(ret != HAL_OK)
|
if (ret != HAL_OK) {
|
||||||
{
|
while (1);
|
||||||
while(1) { ; }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
|
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
|
||||||
|
@ -221,9 +217,8 @@
|
||||||
PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_PCLK1;
|
PeriphClkInitStruct.I2c3ClockSelection = RCC_I2C3CLKSOURCE_PCLK1;
|
||||||
PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PCLK1;
|
PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PCLK1;
|
||||||
ret = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
|
ret = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
|
||||||
if (ret != HAL_OK)
|
if (ret != HAL_OK) {
|
||||||
{
|
while (1);
|
||||||
while(1) { ; }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
|
// Activating the timerprescalers while the APBx prescalers are 1/2/4 will connect the TIMxCLK to HCLK which has been configured to 216MHz
|
||||||
|
@ -280,25 +275,24 @@ void SystemInit(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Enable I-Cache */
|
/* Enable I-Cache */
|
||||||
|
if (INSTRUCTION_CACHE_ENABLE) {
|
||||||
SCB_EnableICache();
|
SCB_EnableICache();
|
||||||
|
}
|
||||||
|
|
||||||
/* Enable D-Cache */
|
/* Enable D-Cache */
|
||||||
//SCB_EnableDCache();
|
if (DATA_CACHE_ENABLE) {
|
||||||
|
SCB_EnableDCache();
|
||||||
|
}
|
||||||
|
|
||||||
/* Configure the system clock to 216 MHz */
|
/* Configure the system clock to 216 MHz */
|
||||||
SystemClock_Config();
|
SystemClock_Config();
|
||||||
|
|
||||||
if(SystemCoreClock != 216000000)
|
if (SystemCoreClock != 216000000) {
|
||||||
{
|
|
||||||
while(1)
|
|
||||||
{
|
|
||||||
// There is a mismatch between the configured clock and the expected clock in portable.h
|
// There is a mismatch between the configured clock and the expected clock in portable.h
|
||||||
|
while (1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||||
|
@ -342,8 +336,7 @@ void SystemCoreClockUpdate(void)
|
||||||
/* Get SYSCLK source -------------------------------------------------------*/
|
/* Get SYSCLK source -------------------------------------------------------*/
|
||||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||||
|
|
||||||
switch (tmp)
|
switch (tmp) {
|
||||||
{
|
|
||||||
case 0x00: /* HSI used as system clock source */
|
case 0x00: /* HSI used as system clock source */
|
||||||
SystemCoreClock = HSI_VALUE;
|
SystemCoreClock = HSI_VALUE;
|
||||||
break;
|
break;
|
||||||
|
@ -358,13 +351,10 @@ void SystemCoreClockUpdate(void)
|
||||||
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
||||||
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
||||||
|
|
||||||
if (pllsource != 0)
|
if (pllsource != 0) {
|
||||||
{
|
|
||||||
/* HSE used as PLL clock source */
|
/* HSE used as PLL clock source */
|
||||||
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||||
}
|
} else {
|
||||||
else
|
|
||||||
{
|
|
||||||
/* HSI used as PLL clock source */
|
/* HSI used as PLL clock source */
|
||||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||||
}
|
}
|
||||||
|
@ -383,15 +373,4 @@ void SystemCoreClockUpdate(void)
|
||||||
SystemCoreClock >>= tmp;
|
SystemCoreClock >>= tmp;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
*/
|
|
||||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
||||||
|
|
|
@ -113,7 +113,8 @@ osd_unittest_SRC := \
|
||||||
$(USER_DIR)/common/typeconversion.c \
|
$(USER_DIR)/common/typeconversion.c \
|
||||||
$(USER_DIR)/drivers/display.c \
|
$(USER_DIR)/drivers/display.c \
|
||||||
$(USER_DIR)/common/maths.c \
|
$(USER_DIR)/common/maths.c \
|
||||||
$(USER_DIR)/common/printf.c
|
$(USER_DIR)/common/printf.c \
|
||||||
|
$(USER_DIR)/fc/runtime_config.c
|
||||||
|
|
||||||
osd_unittest_DEFINES := \
|
osd_unittest_DEFINES := \
|
||||||
OSD
|
OSD
|
||||||
|
|
|
@ -47,10 +47,9 @@ extern "C" {
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
void osdRefresh(timeUs_t currentTimeUs);
|
void osdRefresh(timeUs_t currentTimeUs);
|
||||||
|
void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time);
|
||||||
|
void osdFormatTimer(char *buff, bool showSymbol, int timerIndex);
|
||||||
|
|
||||||
uint8_t stateFlags;
|
|
||||||
uint8_t armingFlags;
|
|
||||||
uint16_t flightModeFlags;
|
|
||||||
uint16_t rssi;
|
uint16_t rssi;
|
||||||
attitudeEulerAngles_t attitude;
|
attitudeEulerAngles_t attitude;
|
||||||
pidProfile_t *currentPidProfile;
|
pidProfile_t *currentPidProfile;
|
||||||
|
@ -272,8 +271,8 @@ TEST(OsdTest, TestStatsImperial)
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_MAX_ALTITUDE] = true;
|
osdConfigMutable()->enabled_stats[OSD_STAT_MAX_ALTITUDE] = true;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_BLACKBOX] = false;
|
osdConfigMutable()->enabled_stats[OSD_STAT_BLACKBOX] = false;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_END_BATTERY] = true;
|
osdConfigMutable()->enabled_stats[OSD_STAT_END_BATTERY] = true;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_FLYTIME] = true;
|
osdConfigMutable()->enabled_stats[OSD_STAT_TIMER_1] = true;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_ARMEDTIME] = true;
|
osdConfigMutable()->enabled_stats[OSD_STAT_TIMER_2] = true;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_MAX_DISTANCE] = true;
|
osdConfigMutable()->enabled_stats[OSD_STAT_MAX_DISTANCE] = true;
|
||||||
osdConfigMutable()->enabled_stats[OSD_STAT_BLACKBOX_NUMBER] = false;
|
osdConfigMutable()->enabled_stats[OSD_STAT_BLACKBOX_NUMBER] = false;
|
||||||
|
|
||||||
|
@ -281,6 +280,14 @@ TEST(OsdTest, TestStatsImperial)
|
||||||
// using imperial unit system
|
// using imperial unit system
|
||||||
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
|
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this timer 1 configuration
|
||||||
|
osdConfigMutable()->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_HUNDREDTHS, 0);
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this timer 2 configuration
|
||||||
|
osdConfigMutable()->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_LAST_ARMED, OSD_TIMER_PREC_SECOND, 0);
|
||||||
|
|
||||||
// and
|
// and
|
||||||
// a GPS fix is present
|
// a GPS fix is present
|
||||||
stateFlags |= GPS_FIX | GPS_FIX_HOME;
|
stateFlags |= GPS_FIX | GPS_FIX_HOME;
|
||||||
|
@ -321,14 +328,15 @@ TEST(OsdTest, TestStatsImperial)
|
||||||
|
|
||||||
// then
|
// then
|
||||||
// statistics screen should display the following
|
// statistics screen should display the following
|
||||||
displayPortTestBufferSubstring(2, 3, "ARMED TIME : 00:04");
|
int row = 3;
|
||||||
displayPortTestBufferSubstring(2, 4, "FLY TIME : 00:07");
|
displayPortTestBufferSubstring(2, row++, "TOTAL ARM : 00:05.00");
|
||||||
displayPortTestBufferSubstring(2, 5, "MAX SPEED : 28");
|
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:03");
|
||||||
displayPortTestBufferSubstring(2, 6, "MAX DISTANCE : 328%c", SYM_FT);
|
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 28");
|
||||||
displayPortTestBufferSubstring(2, 7, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
displayPortTestBufferSubstring(2, row++, "MAX DISTANCE : 328%c", SYM_FT);
|
||||||
displayPortTestBufferSubstring(2, 8, "END BATTERY : 15.2%c", SYM_VOLT);
|
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(2, 9, "MIN RSSI : 25%%");
|
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.2%c", SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(2, 10, "MAX ALTITUDE : 6.5%c", SYM_FT);
|
displayPortTestBufferSubstring(2, row++, "MIN RSSI : 25%%");
|
||||||
|
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 6.5%c", SYM_FT);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -370,14 +378,15 @@ TEST(OsdTest, TestStatsMetric)
|
||||||
|
|
||||||
// then
|
// then
|
||||||
// statistics screen should display the following
|
// statistics screen should display the following
|
||||||
displayPortTestBufferSubstring(2, 3, "ARMED TIME : 00:02");
|
int row = 3;
|
||||||
displayPortTestBufferSubstring(2, 4, "FLY TIME : 00:09");
|
displayPortTestBufferSubstring(2, row++, "TOTAL ARM : 00:07.50");
|
||||||
displayPortTestBufferSubstring(2, 5, "MAX SPEED : 28");
|
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:02");
|
||||||
displayPortTestBufferSubstring(2, 6, "MAX DISTANCE : 100%c", SYM_M);
|
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 28");
|
||||||
displayPortTestBufferSubstring(2, 7, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
displayPortTestBufferSubstring(2, row++, "MAX DISTANCE : 100%c", SYM_M);
|
||||||
displayPortTestBufferSubstring(2, 8, "END BATTERY : 15.2%c", SYM_VOLT);
|
displayPortTestBufferSubstring(2, row++, "MIN BATTERY : 14.7%c", SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(2, 9, "MIN RSSI : 25%%");
|
displayPortTestBufferSubstring(2, row++, "END BATTERY : 15.2%c", SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(2, 10, "MAX ALTITUDE : 2.0%c", SYM_M);
|
displayPortTestBufferSubstring(2, row++, "MIN RSSI : 25%%");
|
||||||
|
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 2.0%c", SYM_M);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -393,16 +402,30 @@ TEST(OsdTest, TestAlarms)
|
||||||
// the following OSD elements are visible
|
// the following OSD elements are visible
|
||||||
osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(8, 1) | VISIBLE_FLAG;
|
osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(8, 1) | VISIBLE_FLAG;
|
||||||
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
|
osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1) | VISIBLE_FLAG;
|
||||||
osdConfigMutable()->item_pos[OSD_FLYTIME] = OSD_POS(1, 1) | VISIBLE_FLAG;
|
osdConfigMutable()->item_pos[OSD_ITEM_TIMER_1] = OSD_POS(20, 1) | VISIBLE_FLAG;
|
||||||
|
osdConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(1, 1) | VISIBLE_FLAG;
|
||||||
osdConfigMutable()->item_pos[OSD_ALTITUDE] = OSD_POS(23, 7) | VISIBLE_FLAG;
|
osdConfigMutable()->item_pos[OSD_ALTITUDE] = OSD_POS(23, 7) | VISIBLE_FLAG;
|
||||||
|
|
||||||
// and
|
// and
|
||||||
// this set of alarm values
|
// this set of alarm values
|
||||||
osdConfigMutable()->rssi_alarm = 20;
|
osdConfigMutable()->rssi_alarm = 20;
|
||||||
osdConfigMutable()->cap_alarm = 2200;
|
osdConfigMutable()->cap_alarm = 2200;
|
||||||
osdConfigMutable()->time_alarm = 1; // in minutes
|
|
||||||
osdConfigMutable()->alt_alarm = 100; // meters
|
osdConfigMutable()->alt_alarm = 100; // meters
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this timer 1 configuration
|
||||||
|
osdConfigMutable()->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_HUNDREDTHS, 2);
|
||||||
|
EXPECT_EQ(OSD_TIMER_SRC_ON, OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1]));
|
||||||
|
EXPECT_EQ(OSD_TIMER_PREC_HUNDREDTHS, OSD_TIMER_PRECISION(osdConfig()->timers[OSD_TIMER_1]));
|
||||||
|
EXPECT_EQ(2, OSD_TIMER_ALARM(osdConfig()->timers[OSD_TIMER_1]));
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this timer 2 configuration
|
||||||
|
osdConfigMutable()->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 1);
|
||||||
|
EXPECT_EQ(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_2]));
|
||||||
|
EXPECT_EQ(OSD_TIMER_PREC_SECOND, OSD_TIMER_PRECISION(osdConfig()->timers[OSD_TIMER_2]));
|
||||||
|
EXPECT_EQ(1, OSD_TIMER_ALARM(osdConfig()->timers[OSD_TIMER_2]));
|
||||||
|
|
||||||
// and
|
// and
|
||||||
// using the metric unit system
|
// using the metric unit system
|
||||||
osdConfigMutable()->units = OSD_UNIT_METRIC;
|
osdConfigMutable()->units = OSD_UNIT_METRIC;
|
||||||
|
@ -424,6 +447,7 @@ TEST(OsdTest, TestAlarms)
|
||||||
displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI);
|
displayPortTestBufferSubstring(8, 1, "%c99", SYM_RSSI);
|
||||||
displayPortTestBufferSubstring(12, 1, "%c16.8%c", SYM_BATT_FULL, SYM_VOLT);
|
displayPortTestBufferSubstring(12, 1, "%c16.8%c", SYM_BATT_FULL, SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer
|
displayPortTestBufferSubstring(1, 1, "%c00:", SYM_FLY_M); // only test the minute part of the timer
|
||||||
|
displayPortTestBufferSubstring(20, 1, "%c01:", SYM_ON_M); // only test the minute part of the timer
|
||||||
displayPortTestBufferSubstring(23, 7, " 0.0%c", SYM_M);
|
displayPortTestBufferSubstring(23, 7, " 0.0%c", SYM_M);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -433,11 +457,8 @@ TEST(OsdTest, TestAlarms)
|
||||||
simulationBatteryState = BATTERY_CRITICAL;
|
simulationBatteryState = BATTERY_CRITICAL;
|
||||||
simulationBatteryVoltage = 135;
|
simulationBatteryVoltage = 135;
|
||||||
simulationAltitude = 12000;
|
simulationAltitude = 12000;
|
||||||
// Fly timer is incremented on periodic calls to osdRefresh, can't simply just increment the simulated system clock
|
simulationTime += 60e6;
|
||||||
for (int i = 0; i < 60; i++) {
|
|
||||||
simulationTime += 1e6;
|
|
||||||
osdRefresh(simulationTime);
|
osdRefresh(simulationTime);
|
||||||
}
|
|
||||||
|
|
||||||
// then
|
// then
|
||||||
// elements showing values in alarm range should flash
|
// elements showing values in alarm range should flash
|
||||||
|
@ -454,6 +475,7 @@ TEST(OsdTest, TestAlarms)
|
||||||
displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI);
|
displayPortTestBufferSubstring(8, 1, "%c12", SYM_RSSI);
|
||||||
displayPortTestBufferSubstring(12, 1, "%c13.5%c", SYM_MAIN_BATT, SYM_VOLT);
|
displayPortTestBufferSubstring(12, 1, "%c13.5%c", SYM_MAIN_BATT, SYM_VOLT);
|
||||||
displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer
|
displayPortTestBufferSubstring(1, 1, "%c01:", SYM_FLY_M); // only test the minute part of the timer
|
||||||
|
displayPortTestBufferSubstring(20, 1, "%c02:", SYM_ON_M); // only test the minute part of the timer
|
||||||
displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M);
|
displayPortTestBufferSubstring(23, 7, " 120.0%c", SYM_M);
|
||||||
} else {
|
} else {
|
||||||
displayPortTestBufferIsEmpty();
|
displayPortTestBufferIsEmpty();
|
||||||
|
@ -495,12 +517,63 @@ TEST(OsdTest, TestElementRssi)
|
||||||
displayPortTestBufferSubstring(8, 1, "%c50", SYM_RSSI);
|
displayPortTestBufferSubstring(8, 1, "%c50", SYM_RSSI);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Tests the time string formatting function with a series of precision settings and time values.
|
||||||
|
*/
|
||||||
|
TEST(OsdTest, TestFormatTimeString)
|
||||||
|
{
|
||||||
|
char buff[OSD_ELEMENT_BUFFER_LENGTH];
|
||||||
|
|
||||||
|
/* Seconds precision, 0 us */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, 0);
|
||||||
|
EXPECT_EQ(0, strcmp("00:00", buff));
|
||||||
|
|
||||||
|
/* Seconds precision, 0.9 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, 0.9e6);
|
||||||
|
EXPECT_EQ(0, strcmp("00:00", buff));
|
||||||
|
|
||||||
|
/* Seconds precision, 10 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, 10e6);
|
||||||
|
EXPECT_EQ(0, strcmp("00:10", buff));
|
||||||
|
|
||||||
|
/* Seconds precision, 1 minute */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, 60e6);
|
||||||
|
EXPECT_EQ(0, strcmp("01:00", buff));
|
||||||
|
|
||||||
|
/* Seconds precision, 1 minute 59 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, 119e6);
|
||||||
|
EXPECT_EQ(0, strcmp("01:59", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 0 us */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 0);
|
||||||
|
EXPECT_EQ(0, strcmp("00:00.00", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 10 milliseconds (one 100th of a second) */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 10e3);
|
||||||
|
EXPECT_EQ(0, strcmp("00:00.01", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 0.9 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 0.9e6);
|
||||||
|
EXPECT_EQ(0, strcmp("00:00.90", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 10 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 10e6);
|
||||||
|
EXPECT_EQ(0, strcmp("00:10.00", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 1 minute */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 60e6);
|
||||||
|
EXPECT_EQ(0, strcmp("01:00.00", buff));
|
||||||
|
|
||||||
|
/* Hundredths precision, 1 minute 59 seconds */
|
||||||
|
osdFormatTime(buff, OSD_TIMER_PREC_HUNDREDTHS, 119e6);
|
||||||
|
EXPECT_EQ(0, strcmp("01:59.00", buff));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// STUBS
|
// STUBS
|
||||||
extern "C" {
|
extern "C" {
|
||||||
bool sensors(uint32_t mask) {
|
void beeperConfirmationBeeps(uint8_t beepCount) {
|
||||||
UNUSED(mask);
|
UNUSED(beepCount);
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool IS_RC_MODE_ACTIVE(boxId_e boxId) {
|
bool IS_RC_MODE_ACTIVE(boxId_e boxId) {
|
||||||
|
@ -574,7 +647,4 @@ extern "C" {
|
||||||
UNUSED(pDisplay);
|
UNUSED(pDisplay);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void setArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); }
|
|
||||||
void unsetArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); }
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -701,4 +701,5 @@ uint8_t stateFlags = 0;
|
||||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||||
rxRuntimeConfig_t rxRuntimeConfig;
|
rxRuntimeConfig_t rxRuntimeConfig;
|
||||||
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
||||||
|
void resetArmingDisabled(void) {}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue