diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 5e49e1cf7f..577d305d52 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -93,13 +93,13 @@ extern const struct serialPortVTable escSerialVTable[]; escSerial_t escSerialPorts[MAX_ESCSERIAL_PORTS]; -void onSerialTimer(timerCCHandlerRec_t *cbRec, captureCompare_t capture); -void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture); +void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture); +void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture); void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture); void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture); static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity); -void setTxSignal(escSerial_t *escSerial, uint8_t state) +void setTxSignalEsc(escSerial_t *escSerial, uint8_t state) { if (state) { IOHi(escSerial->txIO); @@ -118,7 +118,7 @@ static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg) IOConfigGPIO(IOGetByTag(tag), cfg); } -void serialInputPortConfig(const timerHardware_t *timerHardwarePtr) +void serialInputPortConfigEsc(const timerHardware_t *timerHardwarePtr) { #ifdef STM32F10X escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU); @@ -174,7 +174,7 @@ static void serialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t uint32_t timerPeriod=34; TIM_DeInit(timerHardwarePtr->tim); timerConfigure(timerHardwarePtr, timerPeriod, 1); - timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimer); + timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerEsc); timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL); } @@ -198,7 +198,7 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t TIM_DeInit(timerHardwarePtr->tim); timerConfigure(timerHardwarePtr, 0xFFFF, 1); serialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling); - timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChange); + timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc); timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL); } @@ -248,9 +248,9 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac escSerial->escSerialPortIndex = portIndex; escSerial->txIO = IOGetByTag(escSerial->rxTimerHardware->tag); - serialInputPortConfig(escSerial->rxTimerHardware); + serialInputPortConfigEsc(escSerial->rxTimerHardware); - setTxSignal(escSerial, ENABLE); + setTxSignalEsc(escSerial, ENABLE); delay(50); if(mode==0){ @@ -293,7 +293,7 @@ void closeEscSerial(escSerialPortIndex_e portIndex, uint16_t output) /*********************************************/ -void processTxState(escSerial_t *escSerial) +void processTxStateEsc(escSerial_t *escSerial) { uint8_t mask; static uint8_t bitq=0, transmitStart=0; @@ -303,7 +303,7 @@ void processTxState(escSerial_t *escSerial) if(transmitStart==0) { - setTxSignal(escSerial, 1); + setTxSignalEsc(escSerial, 1); } if (!escSerial->isTransmittingData) { char byteToSend; @@ -349,22 +349,22 @@ reload: { if(bitq==0 || bitq==1) { - setTxSignal(escSerial, 1); + setTxSignalEsc(escSerial, 1); } if(bitq==2 || bitq==3) { - setTxSignal(escSerial, 0); + setTxSignalEsc(escSerial, 0); } } else { if(bitq==0 || bitq==2) { - setTxSignal(escSerial, 1); + setTxSignalEsc(escSerial, 1); } if(bitq==1 ||bitq==3) { - setTxSignal(escSerial, 0); + setTxSignalEsc(escSerial, 0); } } bitq++; @@ -383,7 +383,7 @@ reload: if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) { escSerial->isTransmittingData = false; - serialInputPortConfig(escSerial->rxTimerHardware); + serialInputPortConfigEsc(escSerial->rxTimerHardware); } } @@ -425,7 +425,7 @@ void processTxStateBL(escSerial_t *escSerial) mask = escSerial->internalTxBuffer & 1; escSerial->internalTxBuffer >>= 1; - setTxSignal(escSerial, mask); + setTxSignalEsc(escSerial, mask); escSerial->bitsLeftToTransmit--; return; } @@ -434,7 +434,7 @@ void processTxStateBL(escSerial_t *escSerial) if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) { if(escSerial->mode==1) { - serialInputPortConfig(escSerial->rxTimerHardware); + serialInputPortConfigEsc(escSerial->rxTimerHardware); } } } @@ -577,7 +577,7 @@ void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture) } /*-------------------------BL*/ -void extractAndStoreRxByte(escSerial_t *escSerial) +void extractAndStoreRxByteEsc(escSerial_t *escSerial) { if ((escSerial->port.mode & MODE_RX) == 0) { return; @@ -593,7 +593,7 @@ void extractAndStoreRxByte(escSerial_t *escSerial) } } -void onSerialTimer(timerCCHandlerRec_t *cbRec, captureCompare_t capture) +void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture) { UNUSED(capture); escSerial_t *escSerial = container_of(cbRec, escSerial_t, timerCb); @@ -610,10 +610,10 @@ void onSerialTimer(timerCCHandlerRec_t *cbRec, captureCompare_t capture) } - processTxState(escSerial); + processTxStateEsc(escSerial); } -void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) +void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture) { UNUSED(capture); static uint8_t zerofirst=0; @@ -666,7 +666,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) bytes++; if(bytes>3) { - extractAndStoreRxByte(escSerial); + extractAndStoreRxByteEsc(escSerial); } escSerial->internalRxBuffer=0; } diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index aac7f46bb0..9be40e8489 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -18,7 +18,7 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "BETAFC" +#define TARGET_BOARD_IDENTIFIER "BFFC" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE @@ -32,7 +32,7 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define MPU6000_CS_PIN PA15 +#define MPU6000_CS_PIN PC13 #define MPU6000_SPI_INSTANCE SPI1 @@ -78,7 +78,6 @@ #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 5 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 6 - #undef USE_I2C #define USE_SPI @@ -96,8 +95,13 @@ #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 - - +#define OSD +// include the max7456 driver +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI1 +#define MAX7456_SPI_CS_PIN PA1 +#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2) +#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) #define USE_SDCARD #define USE_SDCARD_SPI2 diff --git a/src/main/target/BETAFLIGHTF3/target.mk b/src/main/target/BETAFLIGHTF3/target.mk index 63f46f10be..53222223b6 100755 --- a/src/main/target/BETAFLIGHTF3/target.mk +++ b/src/main/target/BETAFLIGHTF3/target.mk @@ -9,5 +9,6 @@ TARGET_SRC = \ drivers/compass_ak8975.c \ drivers/compass_hmc5883l.c \ drivers/display_ug2864hsweg01.h \ - drivers/flash_m25p16.c - + drivers/flash_m25p16.c \ + drivers/max7456.c \ + io/osd.c \ No newline at end of file diff --git a/stm32.mak b/stm32.mak new file mode 100755 index 0000000000..d60c48e612 --- /dev/null +++ b/stm32.mak @@ -0,0 +1,33 @@ +#This file is generated by VisualGDB. +#It contains GCC settings automatically derived from the board support package (BSP). +#DO NOT EDIT MANUALLY. THE FILE WILL BE OVERWRITTEN. +#Use VisualGDB Project Properties dialog or modify Makefile or per-configuration .mak files instead. + +#VisualGDB provides BSP_ROOT and TOOLCHAIN_ROOT via environment when running Make. The line below will only be active if GNU Make is started manually. +BSP_ROOT ?= $(LOCALAPPDATA)/VisualGDB/EmbeddedBSPs/arm-eabi/com.sysprogs.arm.stm32 +EFP_BASE ?= $(LOCALAPPDATA)/VisualGDB/EmbeddedEFPs +TOOLCHAIN_ROOT ?= C:/Program Files (x86)/GNU Tools ARM Embedded/5.4 2016q2 + +#Embedded toolchain +CC := $(TOOLCHAIN_ROOT)/bin/arm-none-eabi-gcc.exe +CXX := $(TOOLCHAIN_ROOT)/bin/arm-none-eabi-g++.exe +LD := $(CXX) +AR := $(TOOLCHAIN_ROOT)/bin/arm-none-eabi-ar.exe +OBJCOPY := $(TOOLCHAIN_ROOT)/bin/arm-none-eabi-objcopy.exe + +#Additional flags +PREPROCESSOR_MACROS += ARM_MATH_CM3 STM32F103CB +INCLUDE_DIRS += . +LIBRARY_DIRS += +LIBRARY_NAMES += +ADDITIONAL_LINKER_INPUTS += +MACOS_FRAMEWORKS += +LINUX_PACKAGES += + +CFLAGS += +CXXFLAGS += +ASFLAGS += +LDFLAGS += +COMMONFLAGS += -mcpu=cortex-m3 -mthumb +LINKER_SCRIPT := $(BSP_ROOT)/STM32F1xxxx/LinkerScripts/STM32F103CB_flash.lds +