From fefbc4d4bf1bedc52d091be15b921c5f1af81e72 Mon Sep 17 00:00:00 2001 From: mikeller Date: Sun, 12 Jun 2016 00:19:58 +1200 Subject: [PATCH 1/9] Graft of 'serial_rx_telemetry_on_same_port' into development for flight testing by @blckmn. --- src/main/io/serial.c | 21 ++++++++++++++------- src/main/rx/ibus.c | 18 +++++++++++++++++- src/main/rx/sbus.c | 17 ++++++++++++++++- src/main/rx/spektrum.c | 18 +++++++++++++++++- src/main/rx/sumd.c | 18 +++++++++++++++++- src/main/rx/sumh.c | 18 +++++++++++++++++- src/main/rx/xbus.c | 18 +++++++++++++++++- src/main/telemetry/frsky.c | 23 +++++++++++++++-------- src/main/telemetry/ltm.c | 21 ++++++++++++++------- src/main/telemetry/telemetry.c | 7 +++++++ src/main/telemetry/telemetry.h | 5 +++++ 11 files changed, 156 insertions(+), 28 deletions(-) diff --git a/src/main/io/serial.c b/src/main/io/serial.c index a0b5122da3..b2effbb4b7 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -194,7 +194,11 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction return NULL; } +#ifdef TELEMETRY +#define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT) +#else #define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM) +#endif #define ALL_FUNCTIONS_SHARABLE_WITH_MSP (FUNCTION_BLACKBOX | ALL_TELEMETRY_FUNCTIONS_MASK) bool isSerialConfigValid(serialConfig_t *serialConfigToCheck) @@ -203,7 +207,8 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck) /* * rules: * - 1 MSP port minimum, max MSP ports is defined and must be adhered to. - * - Only MSP is allowed to be shared with EITHER any telemetry OR blackbox. + * - MSP is allowed to be shared with EITHER any telemetry OR blackbox. + * - serial RX and FrSky / LTM telemetry can be shared * - No other sharing combinations are valid. */ uint8_t mspPortCount = 0; @@ -223,12 +228,14 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck) return false; } - if (!(portConfig->functionMask & FUNCTION_MSP)) { - return false; - } - - if (!(portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) { - // some other bit must have been set. + if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) { + // MSP & telemetry +#ifdef TELEMETRY + } else if (telemetryCheckRxPortShared(portConfig)) { + // serial RX & telemetry +#endif + } else { + // some other combination return false; } } diff --git a/src/main/rx/ibus.c b/src/main/rx/ibus.c index 299ff4fce2..507df1eff3 100755 --- a/src/main/rx/ibus.c +++ b/src/main/rx/ibus.c @@ -35,6 +35,10 @@ #include "drivers/serial_uart.h" #include "io/serial.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif + #include "rx/rx.h" #include "rx/ibus.h" @@ -64,7 +68,19 @@ bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } - serialPort_t *ibusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, ibusDataReceive, IBUS_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + + serialPort_t *ibusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, ibusDataReceive, IBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = ibusPort; + } +#endif return ibusPort != NULL; } diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 5ae2669751..8613a28fdd 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -32,6 +32,9 @@ #include "drivers/serial_uart.h" #include "io/serial.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif #include "rx/rx.h" #include "rx/sbus.h" @@ -95,8 +98,20 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + portOptions_t options = (rxConfig->sbus_inversion) ? (SBUS_PORT_OPTIONS | SERIAL_INVERTED) : SBUS_PORT_OPTIONS; - serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, SBUS_BAUDRATE, MODE_RX, options); + serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, SBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, options); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = sBusPort; + } +#endif return sBusPort != NULL; } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 39fb03488a..9c0f211028 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -34,6 +34,10 @@ #include "config/config.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif + #include "rx/rx.h" #include "rx/spektrum.h" @@ -95,7 +99,19 @@ bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcRe return false; } - serialPort_t *spektrumPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, spektrumDataReceive, SPEKTRUM_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + + serialPort_t *spektrumPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, spektrumDataReceive, SPEKTRUM_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = spektrumPort; + } +#endif return spektrumPort != NULL; } diff --git a/src/main/rx/sumd.c b/src/main/rx/sumd.c index 5b8fe1e902..8391b8fa0d 100644 --- a/src/main/rx/sumd.c +++ b/src/main/rx/sumd.c @@ -29,6 +29,10 @@ #include "drivers/serial_uart.h" #include "io/serial.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif + #include "rx/rx.h" #include "rx/sumd.h" @@ -63,7 +67,19 @@ bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } - serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumdDataReceive, SUMD_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + + serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumdDataReceive, SUMD_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = sumdPort; + } +#endif return sumdPort != NULL; } diff --git a/src/main/rx/sumh.c b/src/main/rx/sumh.c index 6950b5d90b..87a49fbb72 100644 --- a/src/main/rx/sumh.c +++ b/src/main/rx/sumh.c @@ -35,6 +35,10 @@ #include "drivers/serial_uart.h" #include "io/serial.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif + #include "rx/rx.h" #include "rx/sumh.h" @@ -75,7 +79,19 @@ bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } - sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, MODE_RX, SERIAL_NOT_INVERTED); +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + + sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = sumhPort; + } +#endif return sumhPort != NULL; } diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index a9b8607618..ba70eb579b 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -27,6 +27,10 @@ #include "drivers/serial_uart.h" #include "io/serial.h" +#ifdef TELEMETRY +#include "telemetry/telemetry.h" +#endif + #include "rx/rx.h" #include "rx/xbus.h" @@ -123,7 +127,19 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa return false; } - serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED); +#ifdef TELEMETRY + bool portShared = telemetryCheckRxPortShared(portConfig); +#else + bool portShared = false; +#endif + + serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, xBusDataReceive, baudRate, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); + +#ifdef TELEMETRY + if (portShared) { + telemetrySharedPort = xBusPort; + } +#endif return xBusPort != NULL; } diff --git a/src/main/telemetry/frsky.c b/src/main/telemetry/frsky.c index 9665436a3b..9e59d2709c 100644 --- a/src/main/telemetry/frsky.c +++ b/src/main/telemetry/frsky.c @@ -477,16 +477,23 @@ bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis) void checkFrSkyTelemetryState(void) { - bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing); + if (portConfig && telemetryCheckRxPortShared(portConfig)) { + if (!frskyTelemetryEnabled && telemetrySharedPort != NULL) { + frskyPort = telemetrySharedPort; + frskyTelemetryEnabled = true; + } + } else { + bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing); - if (newTelemetryEnabledValue == frskyTelemetryEnabled) { - return; + if (newTelemetryEnabledValue == frskyTelemetryEnabled) { + return; + } + + if (newTelemetryEnabledValue) + configureFrSkyTelemetryPort(); + else + freeFrSkyTelemetryPort(); } - - if (newTelemetryEnabledValue) - configureFrSkyTelemetryPort(); - else - freeFrSkyTelemetryPort(); } void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle) diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index ad184b5aa6..bca5407492 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -299,12 +299,19 @@ void configureLtmTelemetryPort(void) void checkLtmTelemetryState(void) { - bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ltmPortSharing); - if (newTelemetryEnabledValue == ltmEnabled) - return; - if (newTelemetryEnabledValue) - configureLtmTelemetryPort(); - else - freeLtmTelemetryPort(); + if (portConfig && telemetryCheckRxPortShared(portConfig)) { + if (!ltmEnabled && telemetrySharedPort != NULL) { + ltmPort = telemetrySharedPort; + ltmEnabled = true; + } + } else { + bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ltmPortSharing); + if (newTelemetryEnabledValue == ltmEnabled) + return; + if (newTelemetryEnabledValue) + configureLtmTelemetryPort(); + else + freeLtmTelemetryPort(); + } } #endif diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 4963d9df6e..f4f38ba947 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -74,6 +74,13 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing) return enabled; } +bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig) +{ + return portConfig->functionMask & FUNCTION_RX_SERIAL && portConfig->functionMask & TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK; +} + +serialPort_t *telemetrySharedPort = NULL; + void telemetryCheckState(void) { checkFrSkyTelemetryState(); diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index c53a15776c..8e692c4028 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -48,6 +48,9 @@ typedef struct telemetryConfig_s { uint8_t hottAlarmSoundInterval; } telemetryConfig_t; +bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig); +extern serialPort_t *telemetrySharedPort; + void telemetryCheckState(void); void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle); @@ -55,4 +58,6 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing); void telemetryUseConfig(telemetryConfig_t *telemetryConfig); +#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM) + #endif /* TELEMETRY_COMMON_H_ */ From 0b2aa895798db6ff2d85dff9c7270d087fdd1ab0 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 14 Jun 2016 07:26:26 +0100 Subject: [PATCH 2/9] Tidied .mk file to make them consistent. Fixed EUSTM32F103RC build. --- src/main/target/ALIENFLIGHTF3/target.mk | 5 ++-- src/main/target/ALIENFLIGHTF4/target.mk | 7 +++--- src/main/target/BLUEJAYF4/target.mk | 7 +++--- src/main/target/CC3D/target.mk | 5 ++-- src/main/target/CHEBUZZF3/target.mk | 5 ++-- src/main/target/CJMCU/target.mk | 7 +++--- src/main/target/COLIBRI_RACE/target.mk | 5 ++-- src/main/target/DOGE/target.mk | 7 ++---- src/main/target/EUSTM32F103RC/target.c | 28 +++++++++++----------- src/main/target/EUSTM32F103RC/target.h | 6 ++--- src/main/target/EUSTM32F103RC/target.mk | 3 ++- src/main/target/FURYF3/target.mk | 4 ++-- src/main/target/FURYF4/target.mk | 7 +++--- src/main/target/IRCFUSIONF3/target.mk | 5 ++-- src/main/target/KISSFC/target.mk | 10 ++++---- src/main/target/LUX_RACE/target.mk | 5 +--- src/main/target/MOTOLAB/target.mk | 6 ++--- src/main/target/NAZE/target.mk | 4 ++-- src/main/target/NAZE32PRO/target.mk | 2 +- src/main/target/OLIMEXINO/target.mk | 5 ++-- src/main/target/PORT103R/target.mk | 3 ++- src/main/target/REVO/target.mk | 2 +- src/main/target/RMDO/target.mk | 4 ++-- src/main/target/SINGULARITY/target.mk | 3 +-- src/main/target/SPARKY/target.mk | 6 ++--- src/main/target/SPRACINGF3/target.mk | 5 ++-- src/main/target/SPRACINGF3EVO/target.mk | 4 ++-- src/main/target/SPRACINGF3MINI/target.mk | 4 ++-- src/main/target/STM32F3DISCOVERY/target.mk | 5 ++-- 29 files changed, 85 insertions(+), 84 deletions(-) diff --git a/src/main/target/ALIENFLIGHTF3/target.mk b/src/main/target/ALIENFLIGHTF3/target.mk index 8c802ecd82..fc9d28c289 100644 --- a/src/main/target/ALIENFLIGHTF3/target.mk +++ b/src/main/target/ALIENFLIGHTF3/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP -F3_TARGETS += $(TARGET) TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -9,4 +9,5 @@ TARGET_SRC = \ drivers/accgyro_spi_mpu6500.c \ drivers/compass_ak8963.c \ hardware_revision.c \ - drivers/sonar_hcsr04.c + drivers/sonar_hcsr04.c + diff --git a/src/main/target/ALIENFLIGHTF4/target.mk b/src/main/target/ALIENFLIGHTF4/target.mk index b3c825022c..54a4c3108a 100644 --- a/src/main/target/ALIENFLIGHTF4/target.mk +++ b/src/main/target/ALIENFLIGHTF4/target.mk @@ -1,5 +1,5 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro_mpu6500.c \ @@ -10,4 +10,5 @@ TARGET_SRC = \ drivers/compass_ak8963.c \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f4xx.c + drivers/light_ws2811strip_stm32f4xx.c + diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk index d511472a59..9f23086666 100644 --- a/src/main/target/BLUEJAYF4/target.mk +++ b/src/main/target/BLUEJAYF4/target.mk @@ -1,7 +1,8 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro_spi_mpu6500.c \ drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c + drivers/barometer_ms5611.c + diff --git a/src/main/target/CC3D/target.mk b/src/main/target/CC3D/target.mk index 238eb49068..2718c0302d 100644 --- a/src/main/target/CC3D/target.mk +++ b/src/main/target/CC3D/target.mk @@ -1,5 +1,5 @@ -FEATURES = ONBOARDFLASH HIGHEND VCP F1_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH HIGHEND VCP TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -10,4 +10,5 @@ TARGET_SRC = \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c + drivers/sonar_hcsr04.c + diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk index 8f0ecfe74b..e90db6d09f 100644 --- a/src/main/target/CHEBUZZF3/target.mk +++ b/src/main/target/CHEBUZZF3/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP SDCARD -F3_TARGETS += $(TARGET) TARGET_SRC = \ drivers/light_ws2811strip.c \ @@ -15,4 +15,5 @@ TARGET_SRC = \ drivers/accgyro_l3g4200d.c \ drivers/barometer_ms5611.c \ drivers/barometer_bmp280.c \ - drivers/compass_ak8975.c + drivers/compass_ak8975.c + diff --git a/src/main/target/CJMCU/target.mk b/src/main/target/CJMCU/target.mk index 64a0ebfc02..5aa48e4f21 100644 --- a/src/main/target/CJMCU/target.mk +++ b/src/main/target/CJMCU/target.mk @@ -1,5 +1,5 @@ -FLASH_SIZE = 64 -F1_TARGETS += $(TARGET) +F1_TARGETS += $(TARGET) +FLASH_SIZE = 64 TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -8,4 +8,5 @@ TARGET_SRC = \ hardware_revision.c \ flight/gtune.c \ blackbox/blackbox.c \ - blackbox/blackbox_io.c + blackbox/blackbox_io.c + diff --git a/src/main/target/COLIBRI_RACE/target.mk b/src/main/target/COLIBRI_RACE/target.mk index e029261d0b..3158000738 100644 --- a/src/main/target/COLIBRI_RACE/target.mk +++ b/src/main/target/COLIBRI_RACE/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ io/i2c_bst.c \ @@ -14,4 +14,5 @@ TARGET_SRC = \ drivers/compass_ak8975.c \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c + drivers/light_ws2811strip_stm32f30x.c + diff --git a/src/main/target/DOGE/target.mk b/src/main/target/DOGE/target.mk index 47c076c140..529ed9f58b 100644 --- a/src/main/target/DOGE/target.mk +++ b/src/main/target/DOGE/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -8,8 +8,5 @@ TARGET_SRC = \ drivers/barometer_bmp280.c \ drivers/barometer_spi_bmp280.c \ drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c - - - + drivers/light_ws2811strip_stm32f30x.c diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c index ce76839dd3..99b0b1003b 100644 --- a/src/main/target/EUSTM32F103RC/target.c +++ b/src/main/target/EUSTM32F103RC/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD} // PWM14 - OUT6 + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM1 - RC1 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM2 - RC2 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM3 - RC3 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM4 - RC4 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM5 - RC5 + { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM6 - RC6 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM7 - RC7 + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM8 - RC8 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0 }, // PWM9 - OUT1 + { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0 }, // PWM10 - OUT2 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM11 - OUT3 + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM12 - OUT4 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM13 - OUT5 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0 } // PWM14 - OUT6 }; diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index d00e6ba583..ef7534c663 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -27,12 +27,12 @@ #define USE_EXTI #define MPU6000_CS_GPIO GPIOB -#define MPU6000_CS_PIN GPIO_Pin_12 +#define MPU6000_CS_PIN PB12 #define MPU6000_SPI_INSTANCE SPI2 #define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB #define MPU6500_CS_GPIO GPIOB -#define MPU6500_CS_PIN GPIO_Pin_12 +#define MPU6500_CS_PIN PB12 #define MPU6500_SPI_INSTANCE SPI2 #define GYRO @@ -109,7 +109,7 @@ #define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 #define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 -#define LED_STRIP +//#define LED_STRIP #define LED_STRIP_TIMER TIM3 #define SPEKTRUM_BIND diff --git a/src/main/target/EUSTM32F103RC/target.mk b/src/main/target/EUSTM32F103RC/target.mk index 1801357a01..c12a9fa269 100644 --- a/src/main/target/EUSTM32F103RC/target.mk +++ b/src/main/target/EUSTM32F103RC/target.mk @@ -1,5 +1,5 @@ -FEATURES = ONBOARDFLASH HIGHEND F1_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH HIGHEND DEVICE_FLAGS = -DSTM32F10X_HD @@ -21,3 +21,4 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ drivers/sonar_hcsr04.c + diff --git a/src/main/target/FURYF3/target.mk b/src/main/target/FURYF3/target.mk index c947d79f2e..c68651f01d 100644 --- a/src/main/target/FURYF3/target.mk +++ b/src/main/target/FURYF3/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP SDCARD ONBOARDFLASH -F3_TARGETS += $(TARGET) TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -11,5 +11,5 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/sonar_hcsr04.c \ - drivers/serial_softserial.c + drivers/serial_softserial.c diff --git a/src/main/target/FURYF4/target.mk b/src/main/target/FURYF4/target.mk index c6c3a15733..ef12596bc7 100644 --- a/src/main/target/FURYF4/target.mk +++ b/src/main/target/FURYF4/target.mk @@ -1,8 +1,9 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro_spi_mpu6000.c \ drivers/accgyro_spi_mpu6500.c \ drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c + drivers/barometer_ms5611.c + diff --git a/src/main/target/IRCFUSIONF3/target.mk b/src/main/target/IRCFUSIONF3/target.mk index c58c12fbd6..5c10e856b6 100644 --- a/src/main/target/IRCFUSIONF3/target.mk +++ b/src/main/target/IRCFUSIONF3/target.mk @@ -1,8 +1,9 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP ONBOARDFLASH -F3_TARGETS += $(TARGET) TARGET_FLAGS = -DSPRACINGF3 TARGET_SRC = \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ - drivers/barometer_bmp085.c \ No newline at end of file + drivers/barometer_bmp085.c + diff --git a/src/main/target/KISSFC/target.mk b/src/main/target/KISSFC/target.mk index 6e198e8559..56c635c922 100644 --- a/src/main/target/KISSFC/target.mk +++ b/src/main/target/KISSFC/target.mk @@ -1,10 +1,8 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ - drivers/accgyro_mpu.c \ - drivers/display_ug2864hsweg01.c \ - drivers/accgyro_mpu6050.c - - + drivers/accgyro_mpu.c \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_mpu6050.c diff --git a/src/main/target/LUX_RACE/target.mk b/src/main/target/LUX_RACE/target.mk index 1862327175..1a77b54eae 100644 --- a/src/main/target/LUX_RACE/target.mk +++ b/src/main/target/LUX_RACE/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -9,6 +9,3 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c - - - diff --git a/src/main/target/MOTOLAB/target.mk b/src/main/target/MOTOLAB/target.mk index f2d22aa0ea..9dfcb8bb80 100644 --- a/src/main/target/MOTOLAB/target.mk +++ b/src/main/target/MOTOLAB/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP ONBOARDFLASH F3_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -9,7 +9,5 @@ TARGET_SRC = \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c - - + drivers/serial_softserial.c diff --git a/src/main/target/NAZE/target.mk b/src/main/target/NAZE/target.mk index a73a30ea5d..45d87e4b78 100644 --- a/src/main/target/NAZE/target.mk +++ b/src/main/target/NAZE/target.mk @@ -1,5 +1,5 @@ -FEATURES = ONBOARDFLASH HIGHEND F1_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH HIGHEND TARGET_SRC = \ drivers/accgyro_adxl345.c \ @@ -18,4 +18,4 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ drivers/sonar_hcsr04.c \ - hardware_revision.c \ No newline at end of file + hardware_revision.c diff --git a/src/main/target/NAZE32PRO/target.mk b/src/main/target/NAZE32PRO/target.mk index 7239854ce6..3e5fae6ed9 100644 --- a/src/main/target/NAZE32PRO/target.mk +++ b/src/main/target/NAZE32PRO/target.mk @@ -1,4 +1,4 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ \ No newline at end of file diff --git a/src/main/target/OLIMEXINO/target.mk b/src/main/target/OLIMEXINO/target.mk index bda4796ed1..b299c9ffd4 100644 --- a/src/main/target/OLIMEXINO/target.mk +++ b/src/main/target/OLIMEXINO/target.mk @@ -1,5 +1,5 @@ -FEATURES = HIGHEND F1_TARGETS += $(TARGET) +FEATURES = HIGHEND TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -9,4 +9,5 @@ TARGET_SRC = \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ No newline at end of file + drivers/sonar_hcsr04.c + diff --git a/src/main/target/PORT103R/target.mk b/src/main/target/PORT103R/target.mk index 1801357a01..507b303bff 100644 --- a/src/main/target/PORT103R/target.mk +++ b/src/main/target/PORT103R/target.mk @@ -1,5 +1,5 @@ -FEATURES = ONBOARDFLASH HIGHEND F1_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH HIGHEND DEVICE_FLAGS = -DSTM32F10X_HD @@ -21,3 +21,4 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ drivers/sonar_hcsr04.c + diff --git a/src/main/target/REVO/target.mk b/src/main/target/REVO/target.mk index 148ad83183..21c242fe4b 100644 --- a/src/main/target/REVO/target.mk +++ b/src/main/target/REVO/target.mk @@ -4,5 +4,5 @@ FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_spi_mpu6000.c \ drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c + drivers/compass_hmc5883l.c diff --git a/src/main/target/RMDO/target.mk b/src/main/target/RMDO/target.mk index c3796b11d8..ccbbd5a8e5 100644 --- a/src/main/target/RMDO/target.mk +++ b/src/main/target/RMDO/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP ONBOARDFLASH -F3_TARGETS += $(TARGET) TARGET_FLAGS = -DSPRACINGF3 TARGET_SRC = \ @@ -9,5 +9,5 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_softserial.c \ - drivers/sonar_hcsr04.c + drivers/sonar_hcsr04.c diff --git a/src/main/target/SINGULARITY/target.mk b/src/main/target/SINGULARITY/target.mk index 300133e12a..5e0b22cbe6 100644 --- a/src/main/target/SINGULARITY/target.mk +++ b/src/main/target/SINGULARITY/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP ONBOARDFLASH F3_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -9,4 +9,3 @@ TARGET_SRC = \ drivers/serial_softserial.c \ drivers/vtx_rtc6705.c - diff --git a/src/main/target/SPARKY/target.mk b/src/main/target/SPARKY/target.mk index f02f23ce1b..76ea72b120 100644 --- a/src/main/target/SPARKY/target.mk +++ b/src/main/target/SPARKY/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP F3_TARGETS += $(TARGET) +FEATURES = VCP TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -8,7 +8,5 @@ TARGET_SRC = \ drivers/barometer_bmp280.c \ drivers/compass_ak8975.c \ drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c - - + drivers/light_ws2811strip_stm32f30x.c diff --git a/src/main/target/SPRACINGF3/target.mk b/src/main/target/SPRACINGF3/target.mk index 747e55ea36..00e15bd25f 100644 --- a/src/main/target/SPRACINGF3/target.mk +++ b/src/main/target/SPRACINGF3/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP ONBOARDFLASH F3_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -12,4 +12,5 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_softserial.c \ - drivers/sonar_hcsr04.c + drivers/sonar_hcsr04.c + diff --git a/src/main/target/SPRACINGF3EVO/target.mk b/src/main/target/SPRACINGF3EVO/target.mk index ef081538ba..9b179afe4b 100644 --- a/src/main/target/SPRACINGF3EVO/target.mk +++ b/src/main/target/SPRACINGF3EVO/target.mk @@ -1,5 +1,5 @@ -FEATURES = VCP SDCARD F3_TARGETS += $(TARGET) +FEATURES = VCP SDCARD TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -12,5 +12,5 @@ TARGET_SRC = \ drivers/serial_usb_vcp.c \ drivers/transponder_ir.c \ drivers/transponder_ir_stm32f30x.c \ - io/transponder_ir.c + io/transponder_ir.c diff --git a/src/main/target/SPRACINGF3MINI/target.mk b/src/main/target/SPRACINGF3MINI/target.mk index 4906d10d42..1c1e3b9a52 100644 --- a/src/main/target/SPRACINGF3MINI/target.mk +++ b/src/main/target/SPRACINGF3MINI/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP SDCARD -F3_TARGETS += $(TARGET) TARGET_SRC = \ drivers/accgyro_mpu.c \ @@ -15,5 +15,5 @@ TARGET_SRC = \ drivers/sonar_hcsr04.c \ drivers/transponder_ir.c \ drivers/transponder_ir_stm32f30x.c \ - io/transponder_ir.c + io/transponder_ir.c diff --git a/src/main/target/STM32F3DISCOVERY/target.mk b/src/main/target/STM32F3DISCOVERY/target.mk index 8f0ecfe74b..e90db6d09f 100644 --- a/src/main/target/STM32F3DISCOVERY/target.mk +++ b/src/main/target/STM32F3DISCOVERY/target.mk @@ -1,5 +1,5 @@ +F3_TARGETS += $(TARGET) FEATURES = VCP SDCARD -F3_TARGETS += $(TARGET) TARGET_SRC = \ drivers/light_ws2811strip.c \ @@ -15,4 +15,5 @@ TARGET_SRC = \ drivers/accgyro_l3g4200d.c \ drivers/barometer_ms5611.c \ drivers/barometer_bmp280.c \ - drivers/compass_ak8975.c + drivers/compass_ak8975.c + From 0ddd1e1be1f03d64f4d3eaeeb17d4d87c5d79b40 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 16:46:04 +1000 Subject: [PATCH 3/9] FURYF4 has onboard flash. --- src/main/target/FURYF4/target.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/FURYF4/target.mk b/src/main/target/FURYF4/target.mk index ef12596bc7..e22fad504b 100644 --- a/src/main/target/FURYF4/target.mk +++ b/src/main/target/FURYF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += SDCARD VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_spi_mpu6000.c \ From 1dcb84579bd4d1c2c7839c16c881818fa7b9f25a Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Tue, 14 Jun 2016 10:48:46 +0200 Subject: [PATCH 4/9] Removed top_makefile. Obsolete now that the main Makefile can do all targets recursive. --- top_makefile | 68 ---------------------------------------------------- 1 file changed, 68 deletions(-) delete mode 100644 top_makefile diff --git a/top_makefile b/top_makefile deleted file mode 100644 index 4b1bb90e78..0000000000 --- a/top_makefile +++ /dev/null @@ -1,68 +0,0 @@ -ALL_TARGETS := naze -ALL_TARGETS += cc3d -ALL_TARGETS += cc3d_opbl -ALL_TARGETS += spracingf3 -ALL_TARGETS += spracingf3evo -ALL_TARGETS += spracingf3mini -ALL_TARGETS += sparky -ALL_TARGETS += alienflightf1 -ALL_TARGETS += alienflightf3 -ALL_TARGETS += colibri_race -ALL_TARGETS += lux_race -ALL_TARGETS += motolab -ALL_TARGETS += rmdo -ALL_TARGETS += ircfusionf3 -ALL_TARGETS += afromini -ALL_TARGETS += doge -ALL_TARGETS += singularity - -CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS)) - -clean_naze naze : opts := TARGET=NAZE -clean_cc3d cc3d: opts := TARGET=CC3D -clean_cc3d_opbl cc3d_opbl : opts := TARGET=CC3D_OPBL -clean_spracingf3mini spracingf3mini : opts := TARGET=SPRACINGF3MINI -clean_spracingf3 spracingf3 : opts := TARGET=SPRACINGF3 -clean_spracingf3evo spracingf3evo : opts := TARGET=SPRACINGF3EVO -clean_sparky sparky : opts := TARGET=SPARKY -clean_alienflightf1 alienflightf1 : opts := TARGET=ALIENFLIGHTF1 -clean_alienflightf3 alienflightf3 : opts := TARGET=ALIENFLIGHTF3 -clean_colibri_race colibri_race : opts := TARGET=COLIBRI_RACE -clean_lux_race lux_race : opts := TARGET=LUX_RACE -clean_motolab motolab : opts := TARGET=MOTOLAB -clean_rmdo rmdo : opts := TARGET=RMDO -clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3 -clean_afromini afromini : opts := TARGET=AFROMINI -clean_doge doge : opts := TARGET=DOGE -clean_singularity singularity : opts := TARGET=SINGULARITY - - -.PHONY: all clean -all: everything -clean: clean_everything - - -.PHONY: clean_everything -clean_everything: $(CLEAN_TARGETS) - -.PHONY: everything -everything: $(ALL_TARGETS) - - -.PHONY:$(ALL_TARGETS) -$(ALL_TARGETS): - make -f Makefile hex binary $(opts) - -.PHONY: $(CLEAN_TARGETS) -$(CLEAN_TARGETS): - make -f Makefile clean $(opts) - -.PHONY: help -help: - @echo "This is your new top makefile. synopsis: make " . - @echo "Valid targets": - @echo "all" - @echo "clean" - @echo "$(ALL_TARGETS)" - @echo "$(CLEAN_TARGETS)" - From ea3856f8a8de441b39c61a0d5343f4b8ba69a0dd Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Tue, 14 Jun 2016 12:28:11 +0200 Subject: [PATCH 5/9] Changed recursive all goal for proper return values. Failures had return value 0 (ok). Now also possible to use target name as make goal. Updated help texts to match this change. --- Makefile | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Makefile b/Makefile index 12352a0ba7..53159fa346 100644 --- a/Makefile +++ b/Makefile @@ -658,15 +658,14 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S @$(CC) -c -o $@ $(ASFLAGS) $< -## all : default task; compile C code, build firmware -all: - for build_target in $(VALID_TARGETS); do \ +## all : Build all valid targets +all: $(VALID_TARGETS) + +$(VALID_TARGETS): echo "" && \ - echo "Building $$build_target" && \ - $(MAKE) -j binary hex TARGET=$$build_target || \ - break; \ - echo "Building $$build_target succeeded."; \ - done + echo "Building $@" && \ + $(MAKE) -j binary hex TARGET=$@ && \ + echo "Building $@ succeeded." ## clean : clean up all temporary / machine-generated files clean: @@ -725,6 +724,8 @@ help: Makefile @echo "" @echo "Usage:" @echo " make [TARGET=] [OPTIONS=\"\"]" + @echo "Or:" + @echo " make [OPTIONS=\"\"]" @echo "" @echo "Valid TARGET values are: $(VALID_TARGETS)" @echo "" From b85864305f322324d87f0934fa8568c8f329063d Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 21:45:51 +1000 Subject: [PATCH 6/9] Fixed defines for serial 4 way in IRCFUSIONF3 --- src/main/target/IRCFUSIONF3/target.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 4be3f12b53..3a37a19077 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -108,6 +108,8 @@ // USART3, #define BIND_PIN PB11 +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +/* #define USE_SERIAL_4WAY_BLHELI_BOOTLOADER #define USE_SERIAL_4WAY_SK_BOOTLOADER @@ -125,6 +127,7 @@ #define S1W_RX_GPIO GPIOA #define S1W_RX_PIN GPIO_Pin_10 #endif +*/ // IO - stm32f303cc in 48pin package #define TARGET_IO_PORTA 0xffff From eb118a14213d7e3ed26f43e963c29048ada04bba Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 21:48:33 +1000 Subject: [PATCH 7/9] Fixed target.c for IRCFUSIONF3 --- src/main/target/IRCFUSIONF3/target.c | 37 +++++++++++++--------------- 1 file changed, 17 insertions(+), 20 deletions(-) diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 595b5228a2..828387c1c1 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -81,25 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10}, // PWM3 - PA11 - { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10}, // PWM4 - PA12 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM5 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM6 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM7 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM8 - PA3 - - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; From ab8e423c28c8fef29a1ad5c5bd7e222e5d39bc26 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 22:11:15 +1000 Subject: [PATCH 8/9] NAZE32PRO build fix Removed warning in BMP085 for unused Fixes for RMDO --- src/main/drivers/barometer_bmp085.c | 1 - src/main/sensors/sonar.c | 2 +- src/main/target/NAZE32PRO/target.mk | 2 +- src/main/target/RMDO/target.c | 37 +++++++++++++---------------- 4 files changed, 19 insertions(+), 23 deletions(-) diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index f6dcbfa2c2..951bc62ab9 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -49,7 +49,6 @@ void bmp085_extiHandler(extiCallbackRec_t* cb) isConversionComplete = true; } -static extiCallbackRec_t bmp085_extiCallbackRec; bool bmp085TestEOCConnected(const bmp085Config_t *config); # endif diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 97f1743fd8..6a55389b8f 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -99,7 +99,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon return &sonarHardware; // TODO - move sonar pin selection to CLI -#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) +#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) || defined(RMDO) UNUSED(batteryConfig); static const sonarHardware_t const sonarHardware = { .trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) diff --git a/src/main/target/NAZE32PRO/target.mk b/src/main/target/NAZE32PRO/target.mk index 3e5fae6ed9..0aaf61cb54 100644 --- a/src/main/target/NAZE32PRO/target.mk +++ b/src/main/target/NAZE32PRO/target.mk @@ -1,4 +1,4 @@ F3_TARGETS += $(TARGET) FEATURES = VCP -TARGET_SRC = \ \ No newline at end of file +TARGET_SRC = \ No newline at end of file diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 595b5228a2..fea9723b25 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -81,25 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10}, // PWM3 - PA11 - { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10}, // PWM4 - PA12 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM5 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM6 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM7 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM8 - PA3 - - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1 ,0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1 ,0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1 ,0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1 ,0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2 ,0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2 ,0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2 ,0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2 ,0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1 ,0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1 ,0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10 ,0}, // PWM3 - PA11 + { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10 ,0}, // PWM4 - PA12 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2 ,0}, // PWM5 - PB8 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2 ,0}, // PWM6 - PB9 + { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9 ,0}, // PWM7 - PA2 + { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9 ,0}, // PWM8 - PA3 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6 ,0}, // GPIO_TIMER / LED_STRIP }; From df9a0f186f5a577d781a4659126521fc76faaa21 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 14 Jun 2016 16:20:50 +0100 Subject: [PATCH 9/9] Fixed Singularity target. --- src/main/drivers/vtx_rtc6705.c | 7 ++++--- src/main/drivers/vtx_rtc6705.h | 4 ++-- src/main/io/vtx.c | 17 ++++++++++------- src/main/io/vtx.h | 15 +++++++-------- src/main/target/SINGULARITY/target.mk | 3 ++- 5 files changed, 25 insertions(+), 21 deletions(-) diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index 4bdaf9931d..423bd94ed6 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -100,7 +100,7 @@ static const uint32_t channelArray[RTC6705_BAND_MAX][RTC6705_CHANNEL_MAX] = { * Send a command and return if good * TODO chip detect */ -static bool rtc6705IsReady() +static bool rtc6705IsReady(void) { // Sleep a little bit to make sure it has booted delay(50); @@ -115,7 +115,8 @@ static bool rtc6705IsReady() * This is easier for when generating the frequency to then * reverse the bits afterwards */ -static uint32_t reverse32(uint32_t in) { +static uint32_t reverse32(uint32_t in) +{ uint32_t out = 0; for (uint8_t i = 0 ; i < 32 ; i++) @@ -129,7 +130,7 @@ static uint32_t reverse32(uint32_t in) { /** * Start chip if available */ -bool rtc6705Init() +bool rtc6705Init(void) { DISABLE_RTC6705; spiSetDivisor(RTC6705_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER); diff --git a/src/main/drivers/vtx_rtc6705.h b/src/main/drivers/vtx_rtc6705.h index d72116659f..5f1614fffd 100644 --- a/src/main/drivers/vtx_rtc6705.h +++ b/src/main/drivers/vtx_rtc6705.h @@ -33,6 +33,6 @@ #define RTC6705_FREQ_MIN 5600 #define RTC6705_FREQ_MAX 5950 -bool rtc6705Init(); +bool rtc6705Init(void); void rtc6705SetChannel(uint8_t band, uint8_t channel); -void rtc6705SetFreq(uint16_t freq); \ No newline at end of file +void rtc6705SetFreq(uint16_t freq); diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 3a48bc1a67..cfccf5c5d1 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -35,6 +35,8 @@ #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/serial.h" +#include "drivers/vtx_rtc6705.h" + #include "sensors/sensors.h" #include "sensors/gyro.h" @@ -72,7 +74,7 @@ static uint8_t locked = 0; -void vtxInit() +void vtxInit(void) { rtc6705Init(); if (masterConfig.vtx_mode == 0) { @@ -100,27 +102,27 @@ static void setChannelSaveAndNotify(uint8_t *bandOrChannel, uint8_t step, int32_ } } -void vtxIncrementBand() +void vtxIncrementBand(void) { setChannelSaveAndNotify(&(masterConfig.vtx_band), 1, RTC6705_BAND_MIN, RTC6705_BAND_MAX); } -void vtxDecrementBand() +void vtxDecrementBand(void) { setChannelSaveAndNotify(&(masterConfig.vtx_band), -1, RTC6705_BAND_MIN, RTC6705_BAND_MAX); } -void vtxIncrementChannel() +void vtxIncrementChannel(void) { setChannelSaveAndNotify(&(masterConfig.vtx_channel), 1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX); } -void vtxDecrementChannel() +void vtxDecrementChannel(void) { setChannelSaveAndNotify(&(masterConfig.vtx_channel), -1, RTC6705_CHANNEL_MIN, RTC6705_CHANNEL_MAX); } -void vtxUpdateActivatedChannel() +void vtxUpdateActivatedChannel(void) { if (ARMING_FLAG(ARMED)) { locked = 1; @@ -143,4 +145,5 @@ void vtxUpdateActivatedChannel() } } -#endif \ No newline at end of file +#endif + diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index ddcd7492de..d49c2c7078 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -17,8 +17,6 @@ #pragma once -#include "drivers/vtx_rtc6705.h" - #define VTX_BAND_MIN 1 #define VTX_BAND_MAX 5 #define VTX_CHANNEL_MIN 1 @@ -32,9 +30,10 @@ typedef struct vtxChannelActivationCondition_s { channelRange_t range; } vtxChannelActivationCondition_t; -void vtxInit(); -void vtxIncrementBand(); -void vtxDecrementBand(); -void vtxIncrementChannel(); -void vtxDecrementChannel(); -void vtxUpdateActivatedChannel(); \ No newline at end of file +void vtxInit(void); +void vtxIncrementBand(void); +void vtxDecrementBand(void); +void vtxIncrementChannel(void); +void vtxDecrementChannel(void); +void vtxUpdateActivatedChannel(void); + diff --git a/src/main/target/SINGULARITY/target.mk b/src/main/target/SINGULARITY/target.mk index 5e0b22cbe6..1cd4fcd942 100644 --- a/src/main/target/SINGULARITY/target.mk +++ b/src/main/target/SINGULARITY/target.mk @@ -7,5 +7,6 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_softserial.c \ - drivers/vtx_rtc6705.c + drivers/vtx_rtc6705.c \ + io/vtx.c