From dda662fa861e682a765f3a13841b9c71a59cf8f5 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 23 Jun 2016 08:16:43 +0100 Subject: [PATCH 001/108] Fixed calling of updateRcCommands. --- src/main/mw.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/mw.c b/src/main/mw.c index 5a95f1c924..36dcad2a62 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -694,6 +694,8 @@ void subTaskMainSubprocesses(void) { #endif #if defined(BARO) || defined(SONAR) + // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState + updateRcCommands(); if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { applyAltHold(&masterConfig.airplaneConfig); @@ -874,8 +876,10 @@ void taskUpdateRxMain(void) processRx(); isRXDataNew = true; +#if !defined(BARO) && !defined(SONAR) // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState updateRcCommands(); +#endif updateLEDs(); #ifdef BARO From 6f06be77f8574c50e54ab61095901ceb922de0ae Mon Sep 17 00:00:00 2001 From: mikeller Date: Fri, 24 Jun 2016 21:06:40 +1200 Subject: [PATCH 002/108] Changed 'Makefile' to enable 'make' (without parameters to make use of multicore CPUs. --- Makefile | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index c083a61906..37b2dd292a 100644 --- a/Makefile +++ b/Makefile @@ -664,7 +664,7 @@ all: $(VALID_TARGETS) $(VALID_TARGETS): echo "" && \ echo "Building $@" && \ - $(MAKE) -j binary hex TARGET=$@ && \ + $(MAKE) binary hex TARGET=$@ && \ echo "Building $@ succeeded." ## clean : clean up all temporary / machine-generated files @@ -700,8 +700,11 @@ st-flash_$(TARGET): $(TARGET_BIN) ## st-flash : flash firmware (.bin) onto flight controller st-flash: st-flash_$(TARGET) -binary: $(TARGET_BIN) -hex: $(TARGET_HEX) +binary: + $(MAKE) -j $(TARGET_BIN) + +hex: + $(MAKE) -j $(TARGET_HEX) unbrick_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon From ee860b122ba794dd01d5e5cae3645b9cd26f489e Mon Sep 17 00:00:00 2001 From: rotcehdnih Date: Sun, 26 Jun 2016 16:40:32 +1000 Subject: [PATCH 003/108] X_RACERSPI support for betaflight V3 --- fake_travis_build.sh | 3 +- src/main/target/X_RACERSPI/target.c | 106 ++++++++++++++++++ src/main/target/X_RACERSPI/target.h | 161 +++++++++++++++++++++++++++ src/main/target/X_RACERSPI/target.mk | 15 +++ 4 files changed, 284 insertions(+), 1 deletion(-) create mode 100644 src/main/target/X_RACERSPI/target.c create mode 100644 src/main/target/X_RACERSPI/target.h create mode 100644 src/main/target/X_RACERSPI/target.mk diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 5bae319ada..e9b25f9b26 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -20,7 +20,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=ALIENFLIGHTF3" \ "TARGET=DOGE" \ "TARGET=SINGULARITY" \ - "TARGET=SIRINFPV") + "TARGET=SIRINFPV" \ + "TARGET=X_RACERSPI") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c new file mode 100644 index 0000000000..ff9c8044f8 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.c @@ -0,0 +1,106 @@ + +#include +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // server #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // 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, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP +}; + diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h new file mode 100644 index 0000000000..a655c93e25 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.h @@ -0,0 +1,161 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "X_RACERSPI" + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE + + +#define LED0 PC14 +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define USABLE_TIMER_CHANNEL_COUNT 17 + + + +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH + +#define MPU6000_CS_PIN PA15 +#define MPU6000_SPI_INSTANCE SPI1 + + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW270_DEG + +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW270_DEG + +// MPU6000 interrupts +#define USE_MPU_DATA_READY_SIGNAL +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) +#define MPU_INT_EXTI PC13 +#define USE_EXTI + + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 5 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK +#define UART2_RX_PIN GPIO_Pin_3 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource2 +#define UART2_RX_PINSOURCE GPIO_PinSource3 + +#ifndef UART3_GPIO +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 +#endif + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 +#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 +#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 + + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 +//GPIO_AF_1 + +#define SPI1_NSS_PIN PA15 +#define SPI1_SCK_PIN PB3 +#define SPI1_MISO_PIN PB4 +#define SPI1_MOSI_PIN PB5 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#define LED_STRIP +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX + +#define SPEKTRUM_BIND +// USART3, +#define BIND_PIN PB11 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) + + diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk new file mode 100644 index 0000000000..2b09dc76d6 --- /dev/null +++ b/src/main/target/X_RACERSPI/target.mk @@ -0,0 +1,15 @@ +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.h \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c + From 016886fb3d04fc955bc29ece841ee58cc40096ba Mon Sep 17 00:00:00 2001 From: rotcehdnih Date: Sun, 26 Jun 2016 17:21:20 +1000 Subject: [PATCH 004/108] VARIANT of SPRACINGF3 --- src/main/target/X_RACERSPI/target.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk index 2b09dc76d6..71e749cc2f 100644 --- a/src/main/target/X_RACERSPI/target.mk +++ b/src/main/target/X_RACERSPI/target.mk @@ -1,5 +1,6 @@ F3_TARGETS += $(TARGET) FEATURES = ONBOARDFLASH +TARGET_FLAGS = -DSPRACINGF3 TARGET_SRC = \ drivers/accgyro_mpu.c \ From 27e6034bb5c162c3f73874e2efb6b211d081b15c Mon Sep 17 00:00:00 2001 From: 4712betaflight <4712betaflight@outlook.de> Date: Sun, 26 Jun 2016 13:47:34 +0200 Subject: [PATCH 005/108] Add missing uint32_t tp #585 --- src/main/drivers/serial.c | 2 +- src/main/drivers/serial.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index bb81d3dd89..8a17ce6793 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -56,7 +56,7 @@ void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count) } } -uint8_t serialRxBytesWaiting(serialPort_t *instance) +uint32_t serialRxBytesWaiting(serialPort_t *instance) { return instance->vTable->serialTotalRxWaiting(instance); } diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index d8f868ae79..1f75e931d3 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -81,7 +81,7 @@ struct serialPortVTable { }; void serialWrite(serialPort_t *instance, uint8_t ch); -uint8_t serialRxBytesWaiting(serialPort_t *instance); +uint32_t serialRxBytesWaiting(serialPort_t *instance); uint8_t serialTxBytesFree(serialPort_t *instance); void serialWriteBuf(serialPort_t *instance, uint8_t *data, int count); uint8_t serialRead(serialPort_t *instance); From c14af2506c5b7e85a71d9ffb7977e6ad7440e06c Mon Sep 17 00:00:00 2001 From: rotcehdnih Date: Sun, 26 Jun 2016 23:43:44 +1000 Subject: [PATCH 006/108] Fix whitespace to tab --- fake_travis_build.sh | 48 +++++++++++++++------------- src/main/target/X_RACERSPI/target.mk | 22 ++++++------- 2 files changed, 36 insertions(+), 34 deletions(-) diff --git a/fake_travis_build.sh b/fake_travis_build.sh index e9b25f9b26..6c1077209d 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -1,28 +1,30 @@ #!/bin/bash targets=("PUBLISHMETA=True" \ - "TARGET=CC3D" \ - "TARGET=CC3D_OPBL" \ - "TARGET=COLIBRI_RACE" \ - "TARGET=LUX_RACE" \ - "TARGET=SPRACINGF3" \ - "TARGET=SPRACINGF3EVO" \ - "TARGET=SPRACINGF3MINI" \ - "TARGET=OMNIBUS" \ - "TARGET=NAZE" \ - "TARGET=AFROMINI" \ - "TARGET=RMDO" \ - "TARGET=SPARKY" \ - "TARGET=MOTOLAB" \ - "TARGET=PIKOBLX" \ - "TARGET=IRCFUSIONF3" \ - "TARGET=ALIENFLIGHTF1" \ - "TARGET=ALIENFLIGHTF3" \ - "TARGET=DOGE" \ - "TARGET=SINGULARITY" \ - "TARGET=SIRINFPV" \ + "TARGET=CC3D" \ + "TARGET=CC3D_OPBL" \ + "TARGET=COLIBRI_RACE" \ + "TARGET=LUX_RACE" \ + "TARGET=SPRACINGF3" \ + "TARGET=SPRACINGF3EVO" \ + "TARGET=SPRACINGF3MINI" \ + "TARGET=OMNIBUS" \ + "TARGET=NAZE" \ + "TARGET=AFROMINI" \ + "TARGET=RMDO" \ + "TARGET=SPARKY" \ + "TARGET=MOTOLAB" \ + "TARGET=PIKOBLX" \ + "TARGET=IRCFUSIONF3" \ + "TARGET=ALIENFLIGHTF1" \ + "TARGET=ALIENFLIGHTF3" \ + "TARGET=DOGE" \ + "TARGET=SINGULARITY" \ + "TARGET=SIRINFPV" \ "TARGET=X_RACERSPI") + + #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) export BUILDNAME=${BUILDNAME:=fake_travis} @@ -31,9 +33,9 @@ export TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/simulated} for target in "${targets[@]}" do unset RUNTESTS PUBLISHMETA TARGET - echo - echo - echo "BUILDING '$target'" + echo + echo + echo "BUILDING '$target'" eval "export $target" make -f Makefile clean ./.travis.sh diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk index 71e749cc2f..97b4407297 100644 --- a/src/main/target/X_RACERSPI/target.mk +++ b/src/main/target/X_RACERSPI/target.mk @@ -1,16 +1,16 @@ -F3_TARGETS += $(TARGET) -FEATURES = ONBOARDFLASH +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH TARGET_FLAGS = -DSPRACINGF3 TARGET_SRC = \ drivers/accgyro_mpu.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.h \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ - drivers/sonar_hcsr04.c + drivers/accgyro_spi_mpu6000.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.h \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c From 4d238b27d5d33ed3145b9c5b0424e89ed7380409 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sun, 26 Jun 2016 08:41:24 +0100 Subject: [PATCH 007/108] Moved targetLooptime into gyro_t, tidied gyro_sync and gyro --- src/main/blackbox/blackbox.c | 5 +--- src/main/blackbox/blackbox_io.c | 1 - src/main/config/config.c | 1 - src/main/drivers/accgyro.h | 1 + src/main/drivers/accgyro_mpu.c | 10 ++++--- src/main/drivers/accgyro_mpu.h | 2 +- src/main/drivers/accgyro_mpu3050.c | 1 - src/main/drivers/accgyro_mpu6050.c | 2 +- src/main/drivers/gyro_sync.c | 44 +++++++++++++----------------- src/main/drivers/gyro_sync.h | 7 ++--- src/main/drivers/sensor.h | 2 +- src/main/flight/mixer.c | 1 - src/main/flight/pid.c | 3 +- src/main/io/osd.c | 1 - src/main/io/rc_controls.c | 1 - src/main/io/serial_cli.c | 1 - src/main/io/serial_msp.c | 7 ++--- src/main/main.c | 5 ++-- src/main/mw.c | 2 +- src/main/rx/rx.c | 1 - src/main/sensors/acceleration.c | 1 - src/main/sensors/gyro.c | 20 +++++++------- src/main/sensors/gyro.h | 2 -- src/main/sensors/initialisation.c | 3 +- 24 files changed, 52 insertions(+), 72 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index ed88dd40b1..46bae19584 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -325,9 +325,6 @@ extern uint32_t currentTime; //From rx.c: extern uint16_t rssi; -//From gyro.c -extern uint32_t targetLooptime; - //From rc_controls.c extern uint32_t rcModeActivationMask; @@ -1169,7 +1166,7 @@ static bool blackboxWriteSysinfo() } ); - BLACKBOX_PRINT_HEADER_LINE("looptime:%d", targetLooptime); + BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime); BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 82c105eb4a..7f9b1ec5bd 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -22,7 +22,6 @@ #include "drivers/accgyro.h" #include "drivers/light_led.h" #include "drivers/sound_beeper.h" -#include "drivers/gyro_sync.h" #include "sensors/sensors.h" #include "sensors/boardalignment.h" diff --git a/src/main/config/config.c b/src/main/config/config.c index c371ad2946..b7d404d3d6 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -38,7 +38,6 @@ #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/serial.h" -#include "drivers/gyro_sync.h" #include "drivers/pwm_output.h" #include "drivers/max7456.h" diff --git a/src/main/drivers/accgyro.h b/src/main/drivers/accgyro.h index 385ea90b97..3d90de1bc0 100644 --- a/src/main/drivers/accgyro.h +++ b/src/main/drivers/accgyro.h @@ -27,6 +27,7 @@ typedef struct gyro_s { sensorReadFuncPtr temperature; // read temperature if available sensorInterruptFuncPtr intStatus; float scale; // scalefactor + uint32_t targetLooptime; } gyro_t; typedef struct acc_s { diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 0882581d34..1dbe976090 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -32,7 +32,6 @@ #include "gpio.h" #include "exti.h" #include "bus_i2c.h" -#include "gyro_sync.h" #include "sensor.h" #include "accgyro.h" @@ -300,11 +299,14 @@ bool mpuGyroRead(int16_t *gyroADC) return true; } -void checkMPUDataReady(bool *mpuDataReadyPtr) { +bool checkMPUDataReady(void) +{ + bool ret; if (mpuDataReady) { - *mpuDataReadyPtr = true; + ret = true; mpuDataReady= false; } else { - *mpuDataReadyPtr = false; + ret = false; } + return ret; } diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 6dbfcebf6c..20389147ed 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -185,4 +185,4 @@ void mpuIntExtiInit(void); bool mpuAccRead(int16_t *accData); bool mpuGyroRead(int16_t *gyroADC); mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse); -void checkMPUDataReady(bool *mpuDataReadyPtr); +bool checkMPUDataReady(void); diff --git a/src/main/drivers/accgyro_mpu3050.c b/src/main/drivers/accgyro_mpu3050.c index c974728156..cefaf94b27 100644 --- a/src/main/drivers/accgyro_mpu3050.c +++ b/src/main/drivers/accgyro_mpu3050.c @@ -30,7 +30,6 @@ #include "accgyro.h" #include "accgyro_mpu.h" #include "accgyro_mpu3050.h" -#include "gyro_sync.h" // MPU3050, Standard address 0x68 #define MPU3050_ADDRESS 0x68 diff --git a/src/main/drivers/accgyro_mpu6050.c b/src/main/drivers/accgyro_mpu6050.c index d2717b1350..d4fa0fb846 100644 --- a/src/main/drivers/accgyro_mpu6050.c +++ b/src/main/drivers/accgyro_mpu6050.c @@ -1,4 +1,4 @@ -/* +/* * This file is part of Cleanflight. * * Cleanflight is free software: you can redistribute it and/or modify diff --git a/src/main/drivers/gyro_sync.c b/src/main/drivers/gyro_sync.c index 934708f379..61305e1819 100644 --- a/src/main/drivers/gyro_sync.c +++ b/src/main/drivers/gyro_sync.c @@ -4,48 +4,40 @@ * Created on: 3 aug. 2015 * Author: borisb */ + #include #include -#include #include "platform.h" #include "build_config.h" -#include "common/axis.h" -#include "common/maths.h" - #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/gyro_sync.h" -#include "sensors/sensors.h" -#include "sensors/acceleration.h" - -#include "config/runtime_config.h" -#include "config/config.h" - -extern gyro_t gyro; - -uint32_t targetLooptime; static uint8_t mpuDividerDrops; -bool getMpuDataStatus(gyro_t *gyro) +bool gyroSyncCheckUpdate(const gyro_t *gyro) { - bool mpuDataStatus; if (!gyro->intStatus) - return false; - gyro->intStatus(&mpuDataStatus); - return mpuDataStatus; + return false; + return gyro->intStatus(); } -bool gyroSyncCheckUpdate(void) { - return getMpuDataStatus(&gyro); -} +#define GYRO_LPF_256HZ 0 +#define GYRO_LPF_188HZ 1 +#define GYRO_LPF_98HZ 2 +#define GYRO_LPF_42HZ 3 +#define GYRO_LPF_20HZ 4 +#define GYRO_LPF_10HZ 5 +#define GYRO_LPF_5HZ 6 +#define GYRO_LPF_NONE 7 -void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator) { +uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator) +{ int gyroSamplePeriod; - if (!lpf || lpf == 7) { + if (lpf == GYRO_LPF_256HZ || lpf == GYRO_LPF_NONE) { gyroSamplePeriod = 125; } else { gyroSamplePeriod = 1000; @@ -54,9 +46,11 @@ void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator) { // calculate gyro divider and targetLooptime (expected cycleTime) mpuDividerDrops = gyroSyncDenominator - 1; - targetLooptime = (mpuDividerDrops + 1) * gyroSamplePeriod; + const uint32_t targetLooptime = gyroSyncDenominator * gyroSamplePeriod; + return targetLooptime; } -uint8_t gyroMPU6xxxGetDividerDrops(void) { +uint8_t gyroMPU6xxxGetDividerDrops(void) +{ return mpuDividerDrops; } diff --git a/src/main/drivers/gyro_sync.h b/src/main/drivers/gyro_sync.h index 5c229c689c..f682e218ce 100644 --- a/src/main/drivers/gyro_sync.h +++ b/src/main/drivers/gyro_sync.h @@ -5,8 +5,7 @@ * Author: borisb */ -extern uint32_t targetLooptime; - -bool gyroSyncCheckUpdate(void); +struct gyro_s; +bool gyroSyncCheckUpdate(const struct gyro_s *gyro); uint8_t gyroMPU6xxxGetDividerDrops(void); -void gyroUpdateSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator); +uint32_t gyroSetSampleRate(uint8_t lpf, uint8_t gyroSyncDenominator); diff --git a/src/main/drivers/sensor.h b/src/main/drivers/sensor.h index 6554f8267d..7ae17f5104 100644 --- a/src/main/drivers/sensor.h +++ b/src/main/drivers/sensor.h @@ -22,4 +22,4 @@ typedef void (*sensorInitFuncPtr)(void); // sensor init proto typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype typedef void (*sensorAccInitFuncPtr)(struct acc_s *acc); // sensor init prototype typedef void (*sensorGyroInitFuncPtr)(uint8_t lpf); // gyro sensor init prototype -typedef void (*sensorInterruptFuncPtr)(bool *data); // sensor Interrupt Data Ready +typedef bool (*sensorInterruptFuncPtr)(void); // sensor Interrupt Data Ready diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index e677237899..adc0145ba9 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -36,7 +36,6 @@ #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/system.h" -#include "drivers/gyro_sync.h" #include "rx/rx.h" diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index e1ba582272..91ccbc2d84 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -29,7 +29,6 @@ #include "common/filter.h" #include "drivers/sensor.h" -#include "drivers/gyro_sync.h" #include "drivers/accgyro.h" #include "sensors/sensors.h" @@ -74,7 +73,7 @@ pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we void setTargetPidLooptime(uint8_t pidProcessDenom) { - targetPidLooptime = targetLooptime * pidProcessDenom; + targetPidLooptime = gyro.targetLooptime * pidProcessDenom; } uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index db4c8ad4e0..69f3f56911 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -52,7 +52,6 @@ #include "drivers/inverter.h" #include "drivers/flash_m25p16.h" #include "drivers/sonar_hcsr04.h" -#include "drivers/gyro_sync.h" #include "drivers/usb_io.h" #include "drivers/transponder_ir.h" #include "drivers/sdcard.h" diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 23a87e7641..7eec0de896 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -34,7 +34,6 @@ #include "drivers/system.h" #include "drivers/sensor.h" #include "drivers/accgyro.h" -#include "drivers/gyro_sync.h" #include "sensors/barometer.h" #include "sensors/battery.h" diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 237a5310f1..87df646344 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -48,7 +48,6 @@ #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/sdcard.h" -#include "drivers/gyro_sync.h" #include "drivers/buf_writer.h" diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 3bd8d14415..9f2609c0a0 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -40,7 +40,6 @@ #include "drivers/gpio.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" -#include "drivers/gyro_sync.h" #include "drivers/sdcard.h" #include "drivers/buf_writer.h" #include "drivers/max7456.h" @@ -109,8 +108,8 @@ void setGyroSamplingSpeed(uint16_t looptime) { uint16_t gyroSampleRate = 1000; uint8_t maxDivider = 1; - if (looptime != targetLooptime || looptime == 0) { - if (looptime == 0) looptime = targetLooptime; // needed for pid controller changes + if (looptime != gyro.targetLooptime || looptime == 0) { + if (looptime == 0) looptime = gyro.targetLooptime; // needed for pid controller changes #ifdef STM32F303xC if (looptime < 1000) { masterConfig.gyro_lpf = 0; @@ -854,7 +853,7 @@ static bool processOutCommand(uint8_t cmdMSP) break; case MSP_LOOP_TIME: headSerialReply(2); - serialize16((uint16_t)targetLooptime); + serialize16((uint16_t)gyro.targetLooptime); break; case MSP_RC_TUNING: headSerialReply(11); diff --git a/src/main/main.c b/src/main/main.c index dba36d3f43..686e395048 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -49,7 +49,6 @@ #include "drivers/inverter.h" #include "drivers/flash_m25p16.h" #include "drivers/sonar_hcsr04.h" -#include "drivers/gyro_sync.h" #include "drivers/sdcard.h" #include "drivers/usb_io.h" #include "drivers/transponder_ir.h" @@ -694,12 +693,12 @@ void main_init(void) /* Setup scheduler */ schedulerInit(); - rescheduleTask(TASK_GYROPID, targetLooptime); + rescheduleTask(TASK_GYROPID, gyro.targetLooptime); setTaskEnabled(TASK_GYROPID, true); if(sensors(SENSOR_ACC)) { setTaskEnabled(TASK_ACCEL, true); - switch(targetLooptime) { // Switch statement kept in place to change acc rates in the future + switch(gyro.targetLooptime) { // Switch statement kept in place to change acc rates in the future case(500): case(375): case(250): diff --git a/src/main/mw.c b/src/main/mw.c index 5b282c3e8b..31d6e22c78 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -800,7 +800,7 @@ void taskMainPidLoopCheck(void) const uint32_t startTime = micros(); while (true) { - if (gyroSyncCheckUpdate() || ((currentDeltaTime + (micros() - previousTime)) >= (targetLooptime + GYRO_WATCHDOG_DELAY))) { + if (gyroSyncCheckUpdate(&gyro) || ((currentDeltaTime + (micros() - previousTime)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) { static uint8_t pidUpdateCountdown; if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 5d36956d4a..255fb547ea 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -41,7 +41,6 @@ #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/system.h" -#include "drivers/gyro_sync.h" #include "rx/pwm.h" #include "rx/sbus.h" #include "rx/spektrum.h" diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 320d00ddde..e4471fe308 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -28,7 +28,6 @@ #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/system.h" -#include "drivers/gyro_sync.h" #include "sensors/battery.h" #include "sensors/sensors.h" diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index bce60a1fca..5cd7415266 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -28,7 +28,6 @@ #include "drivers/sensor.h" #include "drivers/accgyro.h" -#include "drivers/gyro_sync.h" #include "sensors/sensors.h" #include "io/beeper.h" #include "io/statusindicator.h" @@ -36,29 +35,30 @@ #include "sensors/gyro.h" -uint16_t calibratingG = 0; +gyro_t gyro; // gyro access functions +sensor_align_e gyroAlign = 0; + int32_t gyroADC[XYZ_AXIS_COUNT]; float gyroADCf[XYZ_AXIS_COUNT]; -int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; +static uint16_t calibratingG = 0; +static int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; static gyroConfig_t *gyroConfig; static biquad_t gyroFilterState[3]; static bool gyroFilterStateIsSet; static float gyroLpfCutFreq; -gyro_t gyro; // gyro access functions -sensor_align_e gyroAlign = 0; - void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz) { gyroConfig = gyroConfigToUse; gyroLpfCutFreq = gyro_lpf_hz; } -void initGyroFilterCoefficients(void) { +void initGyroFilterCoefficients(void) +{ int axis; - if (gyroLpfCutFreq && targetLooptime) { /* Initialisation needs to happen once samplingrate is known */ - for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], targetLooptime); + if (gyroLpfCutFreq && gyro.targetLooptime) { /* Initialisation needs to happen once samplingrate is known */ + for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], gyro.targetLooptime); gyroFilterStateIsSet = true; } } @@ -79,7 +79,7 @@ bool isOnFinalGyroCalibrationCycle(void) } uint16_t calculateCalibratingCycles(void) { - return (CALIBRATING_GYRO_CYCLES / targetLooptime) * CALIBRATING_GYRO_CYCLES; + return (CALIBRATING_GYRO_CYCLES / gyro.targetLooptime) * CALIBRATING_GYRO_CYCLES; } bool isOnFirstGyroCalibrationCycle(void) diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 04a5188a05..075cccbe69 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -31,11 +31,9 @@ typedef enum { } gyroSensor_e; extern gyro_t gyro; -extern sensor_align_e gyroAlign; extern int32_t gyroADC[XYZ_AXIS_COUNT]; extern float gyroADCf[XYZ_AXIS_COUNT]; -extern int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT]; typedef struct gyroConfig_s { uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 00093d18e6..df394c7a69 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -79,6 +79,7 @@ extern float magneticDeclination; extern gyro_t gyro; extern baro_t baro; extern acc_t acc; +extern sensor_align_e gyroAlign; uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; @@ -632,7 +633,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a acc.init(&acc); } // this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here. - gyroUpdateSampleRate(gyroLpf, gyroSyncDenominator); // Set gyro refresh rate before initialisation + gyro.targetLooptime = gyroSetSampleRate(gyroLpf, gyroSyncDenominator); // Set gyro sample rate before initialisation gyro.init(gyroLpf); detectMag(magHardwareToUse); From 75237dd2099351512368617ae4b9df9be78080a1 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sun, 26 Jun 2016 16:14:17 +0100 Subject: [PATCH 008/108] Fixed up gyro init. --- src/main/config/config.c | 2 +- src/main/io/rc_controls.c | 2 +- src/main/main.c | 2 +- src/main/mw.c | 2 +- src/main/sensors/gyro.c | 53 +++++++++++++------------------ src/main/sensors/gyro.h | 5 +-- src/main/sensors/initialisation.c | 1 + 7 files changed, 30 insertions(+), 37 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index b7d404d3d6..2c0c9c17d9 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -750,7 +750,7 @@ void activateConfig(void) ¤tProfile->pidProfile ); - useGyroConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz); + gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz); #ifdef TELEMETRY telemetryUseConfig(&masterConfig.telemetryConfig); diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 7eec0de896..0848670dbc 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -209,7 +209,7 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { // GYRO calibration - gyroSetCalibrationCycles(calculateCalibratingCycles()); + gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); #ifdef GPS if (feature(FEATURE_GPS)) { diff --git a/src/main/main.c b/src/main/main.c index 686e395048..c6cf2ffb29 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -625,7 +625,7 @@ void init(void) if (masterConfig.mixerMode == MIXER_GIMBAL) { accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); } - gyroSetCalibrationCycles(calculateCalibratingCycles()); + gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); #ifdef BARO baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES); #endif diff --git a/src/main/mw.c b/src/main/mw.c index 31d6e22c78..65abe6b484 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -377,7 +377,7 @@ void mwArm(void) static bool firstArmingCalibrationWasCompleted; if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) { - gyroSetCalibrationCycles(calculateCalibratingCycles()); + gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); armingCalibrationWasInitialised = true; firstArmingCalibrationWasCompleted = true; } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 5cd7415266..fc28705bf9 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -45,21 +45,20 @@ static uint16_t calibratingG = 0; static int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; static gyroConfig_t *gyroConfig; static biquad_t gyroFilterState[3]; -static bool gyroFilterStateIsSet; -static float gyroLpfCutFreq; +static uint8_t gyroLpfHz; -void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz) +void gyroUseConfig(gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz) { gyroConfig = gyroConfigToUse; - gyroLpfCutFreq = gyro_lpf_hz; + gyroLpfHz = gyro_lpf_hz; } -void initGyroFilterCoefficients(void) +void gyroInit(void) { - int axis; - if (gyroLpfCutFreq && gyro.targetLooptime) { /* Initialisation needs to happen once samplingrate is known */ - for (axis = 0; axis < 3; axis++) BiQuadNewLpf(gyroLpfCutFreq, &gyroFilterState[axis], gyro.targetLooptime); - gyroFilterStateIsSet = true; + if (gyroLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known + for (int axis = 0; axis < 3; axis++) { + BiQuadNewLpf(gyroLpfHz, &gyroFilterState[axis], gyro.targetLooptime); + } } } @@ -73,27 +72,27 @@ bool isGyroCalibrationComplete(void) return calibratingG == 0; } -bool isOnFinalGyroCalibrationCycle(void) +static bool isOnFinalGyroCalibrationCycle(void) { return calibratingG == 1; } -uint16_t calculateCalibratingCycles(void) { +uint16_t gyroCalculateCalibratingCycles(void) +{ return (CALIBRATING_GYRO_CYCLES / gyro.targetLooptime) * CALIBRATING_GYRO_CYCLES; } -bool isOnFirstGyroCalibrationCycle(void) +static bool isOnFirstGyroCalibrationCycle(void) { - return calibratingG == calculateCalibratingCycles(); + return calibratingG == gyroCalculateCalibratingCycles(); } static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThreshold) { - int8_t axis; static int32_t g[3]; static stdev_t var[3]; - for (axis = 0; axis < 3; axis++) { + for (int axis = 0; axis < 3; axis++) { // Reset g[axis] at start of calibration if (isOnFirstGyroCalibrationCycle()) { @@ -113,10 +112,10 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho float dev = devStandardDeviation(&var[axis]); // check deviation and startover in case the model was moved if (gyroMovementCalibrationThreshold && dev > gyroMovementCalibrationThreshold) { - gyroSetCalibrationCycles(calculateCalibratingCycles()); + gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); return; } - gyroZero[axis] = (g[axis] + (calculateCalibratingCycles() / 2)) / calculateCalibratingCycles(); + gyroZero[axis] = (g[axis] + (gyroCalculateCalibratingCycles() / 2)) / gyroCalculateCalibratingCycles(); } } @@ -129,8 +128,7 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho static void applyGyroZero(void) { - int8_t axis; - for (axis = 0; axis < 3; axis++) { + for (int axis = 0; axis < 3; axis++) { gyroADC[axis] -= gyroZero[axis]; } } @@ -138,14 +136,13 @@ static void applyGyroZero(void) void gyroUpdate(void) { int16_t gyroADCRaw[XYZ_AXIS_COUNT]; - int axis; // range: +/- 8192; +/- 2000 deg/sec if (!gyro.read(gyroADCRaw)) { return; } - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { if (debugMode == DEBUG_GYRO) debug[axis] = gyroADC[axis]; gyroADC[axis] = gyroADCRaw[axis]; } @@ -158,16 +155,10 @@ void gyroUpdate(void) applyGyroZero(); - if (gyroLpfCutFreq) { - if (!gyroFilterStateIsSet) initGyroFilterCoefficients(); /* initialise filter coefficients */ - - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - if (gyroFilterStateIsSet) { - gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]); - gyroADC[axis] = lrintf(gyroADCf[axis]); - } else { - gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled - } + if (gyroLpfHz) { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + gyroADCf[axis] = applyBiQuadFilter((float)gyroADC[axis], &gyroFilterState[axis]); + gyroADC[axis] = lrintf(gyroADCf[axis]); } } } diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 075cccbe69..7a8214092c 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -39,9 +39,10 @@ typedef struct gyroConfig_s { uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. } gyroConfig_t; -void useGyroConfig(gyroConfig_t *gyroConfigToUse, float gyro_lpf_hz); +void gyroUseConfig(gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz); void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired); +void gyroInit(void); void gyroUpdate(void); bool isGyroCalibrationComplete(void); -uint16_t calculateCalibratingCycles(void); +uint16_t gyroCalculateCalibratingCycles(void); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index df394c7a69..80d6169518 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -635,6 +635,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a // this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here. gyro.targetLooptime = gyroSetSampleRate(gyroLpf, gyroSyncDenominator); // Set gyro sample rate before initialisation gyro.init(gyroLpf); + gyroInit(); detectMag(magHardwareToUse); From f3eb19430149ba58c74e1e06dd6dcfc22c334b76 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 27 Jun 2016 06:16:23 +1000 Subject: [PATCH 009/108] Update README.md Logo change --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 0239f59611..28d9c66a13 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Betaflight -![Betaflight](https://dl.dropboxusercontent.com/u/31537757/betaflight%20logo.jpg) +![Betaflight](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088900-228-bf_logo.jpg) Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft. From 67f7ae7206ad8cb1a9aed196216dfdc4bcee136e Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 27 Jun 2016 06:34:25 +1000 Subject: [PATCH 010/108] Using githubusercontent for logo --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 28d9c66a13..0253334eff 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Betaflight -![Betaflight](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088900-228-bf_logo.jpg) +![Betaflight](https://camo.githubusercontent.com/8178215d6cb90842dc95c9d437b1bdf09b2d57a7/687474703a2f2f7374617469632e726367726f7570732e6e65742f666f72756d732f6174746163686d656e74732f362f312f302f332f372f362f61393038383930302d3232382d62665f6c6f676f2e6a7067) Clean-code version of baseflight flight-controller - flight controllers are used to fly multi-rotor craft and fixed wing craft. From deaeb23c84cd65d27afc12e134a8f0da8e2d3b76 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 27 Jun 2016 06:42:21 +1000 Subject: [PATCH 011/108] fixed incompatible pointer types in softserial --- src/main/drivers/serial_softserial.c | 2 +- src/main/drivers/serial_softserial.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index f5ed4d5931..a2ad403b26 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -408,7 +408,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture) } } -uint8_t softSerialRxBytesWaiting(serialPort_t *instance) +uint32_t softSerialRxBytesWaiting(serialPort_t *instance) { if ((instance->mode & MODE_RX) == 0) { return 0; diff --git a/src/main/drivers/serial_softserial.h b/src/main/drivers/serial_softserial.h index daa9c5c64e..af80423b07 100644 --- a/src/main/drivers/serial_softserial.h +++ b/src/main/drivers/serial_softserial.h @@ -28,7 +28,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb // serialPort API void softSerialWriteByte(serialPort_t *instance, uint8_t ch); -uint8_t softSerialRxBytesWaiting(serialPort_t *instance); +uint32_t softSerialRxBytesWaiting(serialPort_t *instance); uint8_t softSerialTxBytesFree(serialPort_t *instance); uint8_t softSerialReadByte(serialPort_t *instance); void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate); From d069945f894eb7ac2848eb19d8e6abf7bb529c3b Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sun, 26 Jun 2016 21:43:04 +0100 Subject: [PATCH 012/108] Improved gyroSetCalibrationCycles parameters. --- src/main/io/rc_controls.c | 2 +- src/main/main.c | 2 +- src/main/mw.c | 2 +- src/main/sensors/gyro.c | 32 ++++++++++++++++---------------- src/main/sensors/gyro.h | 5 ++--- 5 files changed, 21 insertions(+), 22 deletions(-) diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 0848670dbc..fdea810034 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -209,7 +209,7 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { // GYRO calibration - gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); + gyroSetCalibrationCycles(); #ifdef GPS if (feature(FEATURE_GPS)) { diff --git a/src/main/main.c b/src/main/main.c index c6cf2ffb29..743f771785 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -625,7 +625,7 @@ void init(void) if (masterConfig.mixerMode == MIXER_GIMBAL) { accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); } - gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); + gyroSetCalibrationCycles(); #ifdef BARO baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES); #endif diff --git a/src/main/mw.c b/src/main/mw.c index 65abe6b484..bf97c56a2d 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -377,7 +377,7 @@ void mwArm(void) static bool firstArmingCalibrationWasCompleted; if (masterConfig.gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) { - gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); + gyroSetCalibrationCycles(); armingCalibrationWasInitialised = true; firstArmingCalibrationWasCompleted = true; } diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index fc28705bf9..48113e934a 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -41,32 +41,27 @@ sensor_align_e gyroAlign = 0; int32_t gyroADC[XYZ_AXIS_COUNT]; float gyroADCf[XYZ_AXIS_COUNT]; -static uint16_t calibratingG = 0; static int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; -static gyroConfig_t *gyroConfig; -static biquad_t gyroFilterState[3]; -static uint8_t gyroLpfHz; +static const gyroConfig_t *gyroConfig; +static biquad_t gyroFilterState[XYZ_AXIS_COUNT]; +static uint8_t gyroSoftLpfHz; +static uint16_t calibratingG = 0; -void gyroUseConfig(gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz) +void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz) { gyroConfig = gyroConfigToUse; - gyroLpfHz = gyro_lpf_hz; + gyroSoftLpfHz = gyro_soft_lpf_hz; } void gyroInit(void) { - if (gyroLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known + if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known for (int axis = 0; axis < 3; axis++) { - BiQuadNewLpf(gyroLpfHz, &gyroFilterState[axis], gyro.targetLooptime); + BiQuadNewLpf(gyroSoftLpfHz, &gyroFilterState[axis], gyro.targetLooptime); } } } -void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired) -{ - calibratingG = calibrationCyclesRequired; -} - bool isGyroCalibrationComplete(void) { return calibratingG == 0; @@ -77,7 +72,7 @@ static bool isOnFinalGyroCalibrationCycle(void) return calibratingG == 1; } -uint16_t gyroCalculateCalibratingCycles(void) +static uint16_t gyroCalculateCalibratingCycles(void) { return (CALIBRATING_GYRO_CYCLES / gyro.targetLooptime) * CALIBRATING_GYRO_CYCLES; } @@ -87,6 +82,11 @@ static bool isOnFirstGyroCalibrationCycle(void) return calibratingG == gyroCalculateCalibratingCycles(); } +void gyroSetCalibrationCycles(void) +{ + calibratingG = gyroCalculateCalibratingCycles(); +} + static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThreshold) { static int32_t g[3]; @@ -112,7 +112,7 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho float dev = devStandardDeviation(&var[axis]); // check deviation and startover in case the model was moved if (gyroMovementCalibrationThreshold && dev > gyroMovementCalibrationThreshold) { - gyroSetCalibrationCycles(gyroCalculateCalibratingCycles()); + gyroSetCalibrationCycles(); return; } gyroZero[axis] = (g[axis] + (gyroCalculateCalibratingCycles() / 2)) / gyroCalculateCalibratingCycles(); @@ -155,7 +155,7 @@ void gyroUpdate(void) applyGyroZero(); - if (gyroLpfHz) { + if (gyroSoftLpfHz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { gyroADCf[axis] = applyBiQuadFilter((float)gyroADC[axis], &gyroFilterState[axis]); gyroADC[axis] = lrintf(gyroADCf[axis]); diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 7a8214092c..54069b8a64 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -39,10 +39,9 @@ typedef struct gyroConfig_s { uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. } gyroConfig_t; -void gyroUseConfig(gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz); -void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired); +void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz); +void gyroSetCalibrationCycles(void); void gyroInit(void); void gyroUpdate(void); bool isGyroCalibrationComplete(void); -uint16_t gyroCalculateCalibratingCycles(void); From 6b5ffd14505a65e50561b61bd7f83490c375728b Mon Sep 17 00:00:00 2001 From: rotcehdnih Date: Mon, 27 Jun 2016 08:02:57 +1000 Subject: [PATCH 013/108] tab to space --- fake_travis_build.sh | 42 ++++++++++++++-------------- src/main/target/X_RACERSPI/target.mk | 24 ++++++++-------- 2 files changed, 33 insertions(+), 33 deletions(-) diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 6c1077209d..1a2c9af909 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -1,27 +1,27 @@ #!/bin/bash targets=("PUBLISHMETA=True" \ - "TARGET=CC3D" \ - "TARGET=CC3D_OPBL" \ - "TARGET=COLIBRI_RACE" \ - "TARGET=LUX_RACE" \ - "TARGET=SPRACINGF3" \ - "TARGET=SPRACINGF3EVO" \ - "TARGET=SPRACINGF3MINI" \ - "TARGET=OMNIBUS" \ - "TARGET=NAZE" \ - "TARGET=AFROMINI" \ - "TARGET=RMDO" \ - "TARGET=SPARKY" \ - "TARGET=MOTOLAB" \ - "TARGET=PIKOBLX" \ - "TARGET=IRCFUSIONF3" \ - "TARGET=ALIENFLIGHTF1" \ - "TARGET=ALIENFLIGHTF3" \ - "TARGET=DOGE" \ - "TARGET=SINGULARITY" \ - "TARGET=SIRINFPV" \ - "TARGET=X_RACERSPI") + "TARGET=CC3D" \ + "TARGET=CC3D_OPBL" \ + "TARGET=COLIBRI_RACE" \ + "TARGET=LUX_RACE" \ + "TARGET=SPRACINGF3" \ + "TARGET=SPRACINGF3EVO" \ + "TARGET=SPRACINGF3MINI" \ + "TARGET=OMNIBUS" \ + "TARGET=NAZE" \ + "TARGET=AFROMINI" \ + "TARGET=RMDO" \ + "TARGET=SPARKY" \ + "TARGET=MOTOLAB" \ + "TARGET=PIKOBLX" \ + "TARGET=IRCFUSIONF3" \ + "TARGET=ALIENFLIGHTF1" \ + "TARGET=ALIENFLIGHTF3" \ + "TARGET=DOGE" \ + "TARGET=SINGULARITY" \ + "TARGET=SIRINFPV" \ + "TARGET=X_RACERSPI") diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk index 97b4407297..c0c219bd30 100644 --- a/src/main/target/X_RACERSPI/target.mk +++ b/src/main/target/X_RACERSPI/target.mk @@ -1,16 +1,16 @@ -F3_TARGETS += $(TARGET) -FEATURES = ONBOARDFLASH +F3_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH TARGET_FLAGS = -DSPRACINGF3 TARGET_SRC = \ - drivers/accgyro_mpu.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.h \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ - drivers/sonar_hcsr04.c + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.h \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c From 16d9a952a2b7bad70a3e84336b6eb55377f16925 Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Mon, 27 Jun 2016 14:12:02 +0200 Subject: [PATCH 014/108] Added I2C clock stretching. --- src/main/drivers/bus_i2c_stm32f10x.c | 3 +++ src/main/drivers/bus_i2c_stm32f30x.c | 2 ++ 2 files changed, 5 insertions(+) diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index c7e972b2d7..72cf8769c2 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -422,6 +422,9 @@ void i2cInit(I2CDevice device) I2C_Cmd(i2c->dev, ENABLE); I2C_Init(i2c->dev, &i2cInit); + + I2C_StretchClockCmd(i2c->dev, ENABLE); + // I2C ER Interrupt nvic.NVIC_IRQChannel = i2c->er_irq; diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index c324d03e7a..8599d02f53 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -101,6 +101,8 @@ void i2cInit(I2CDevice device) I2C_Init(I2Cx, &i2cInit); + I2C_StretchClockCmd(I2Cx, ENABLE); + I2C_Cmd(I2Cx, ENABLE); } From afda764e45c4af82be7d242133da743616317500 Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Mon, 27 Jun 2016 18:38:43 +0200 Subject: [PATCH 015/108] Tidy up the Makefile clean rules, same way main build/all rules was made. Single target clean now available as make goals. --- Makefile | 34 +++++++++++++++++++++++----------- 1 file changed, 23 insertions(+), 11 deletions(-) diff --git a/Makefile b/Makefile index c083a61906..d97613b3e4 100644 --- a/Makefile +++ b/Makefile @@ -667,24 +667,36 @@ $(VALID_TARGETS): $(MAKE) -j binary hex TARGET=$@ && \ echo "Building $@ succeeded." -## clean : clean up all temporary / machine-generated files + + +CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) +TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) + +## clean : clean up temporary / machine-generated files clean: + echo "Cleaning $(TARGET)" rm -f $(CLEAN_ARTIFACTS) rm -rf $(OBJECT_DIR)/$(TARGET) + echo "Cleaning $(TARGET) succeeded." -## clean_test : clean up all temporary / machine-generated files (tests) +## clean_test : clean up temporary / machine-generated files (tests) clean_test: cd src/test && $(MAKE) clean || true -## clean_all_targets : clean all valid target platforms -clean_all: - for clean_target in $(VALID_TARGETS); do \ - echo "" && \ - echo "Cleaning $$clean_target" && \ - $(MAKE) -j TARGET=$$clean_target clean || \ - break; \ - echo "Cleaning $$clean_target succeeded."; \ - done +## clean_ : clean up one specific target +$(CLEAN_TARGETS) : + $(MAKE) -j TARGET=$(subst clean_,,$@) clean + +## _clean : clean up one specific target (alias for above) +$(TARGETS_CLEAN) : + $(MAKE) -j TARGET=$(subst _clean,,$@) clean + +## clean_all : clean all valid targets +clean_all:$(CLEAN_TARGETS) + +## all_clean : clean all valid targets (alias for above) +all_clean:$(TARGETS_CLEAN) + flash_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon From 224043be4e0a201733b8369231949c1fe7e79ca3 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Mon, 27 Jun 2016 10:55:41 -0700 Subject: [PATCH 016/108] MAX7456 driver - add support for SPI DMA --- src/main/drivers/bus_spi.c | 3 +- src/main/drivers/max7456.c | 208 ++++++++++++++++++---------- src/main/drivers/max7456.h | 12 +- src/main/drivers/nvic.h | 1 + src/main/io/osd.c | 217 ++++++++++++++++++++---------- src/main/target/SIRINFPV/target.h | 7 + 6 files changed, 301 insertions(+), 147 deletions(-) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 5af40d0750..c4d53145cc 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -358,4 +358,5 @@ void spiResetErrorCounter(SPI_TypeDef *instance) SPIDevice device = spiDeviceByInstance(instance); if (device != SPIINVALID) spiHardwareMap[device].errorCount = 0; -} \ No newline at end of file +} + diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index b8a59bcfc9..fa2fbc245e 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -29,6 +29,7 @@ #include "drivers/bus_spi.h" #include "drivers/light_led.h" #include "drivers/system.h" +#include "drivers/nvic.h" #include "max7456.h" #include "max7456_symbols.h" @@ -36,30 +37,120 @@ #define DISABLE_MAX7456 IOHi(max7456CsPin) #define ENABLE_MAX7456 IOLo(max7456CsPin) -/** Artificial Horizon limits **/ -#define AHIPITCHMAX 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees -#define AHIROLLMAX 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees -#define AHISIDEBARWIDTHPOSITION 7 -#define AHISIDEBARHEIGHTPOSITION 3 - uint16_t max_screen_size; -char max7456_screen[VIDEO_BUFFER_CHARS_PAL]; +static MAX7456_CHAR_TYPE max7456_screen[VIDEO_BUFFER_CHARS_PAL + 5]; +#define SCREEN_BUFFER ((MAX7456_CHAR_TYPE*)&max7456_screen[3]) + +#ifdef MAX7456_DMA_CHANNEL_TX +volatile uint8_t dma_transaction_in_progress = 0; +#endif static uint8_t video_signal_type = 0; static uint8_t max7456_lock = 0; static IO_t max7456CsPin = IO_NONE; -uint8_t max7456_send(uint8_t add, uint8_t data) { + +MAX7456_CHAR_TYPE* max7456_get_screen_buffer(void) { + return SCREEN_BUFFER; +} + +static uint8_t max7456_send(uint8_t add, uint8_t data) { spiTransferByte(MAX7456_SPI_INSTANCE, add); return spiTransferByte(MAX7456_SPI_INSTANCE, data); } +#ifdef MAX7456_DMA_CHANNEL_TX +static void max7456_send_dma(void* tx_buffer, void* rx_buffer, uint16_t buffer_size) { + DMA_InitTypeDef DMA_InitStructure; +#ifdef MAX7456_DMA_CHANNEL_RX + static uint16_t dummy[] = {0xffff}; +#else + UNUSED(rx_buffer); +#endif + while (dma_transaction_in_progress); // Wait for prev DMA transaction + + DMA_DeInit(MAX7456_DMA_CHANNEL_TX); +#ifdef MAX7456_DMA_CHANNEL_RX + DMA_DeInit(MAX7456_DMA_CHANNEL_RX); +#endif + + // Common to both channels + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)(&(MAX7456_SPI_INSTANCE->DR)); + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_BufferSize = buffer_size; + DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; + DMA_InitStructure.DMA_Priority = DMA_Priority_Low; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; + +#ifdef MAX7456_DMA_CHANNEL_RX + // Rx Channel + DMA_InitStructure.DMA_MemoryBaseAddr = rx_buffer ? (uint32_t)rx_buffer : (uint32_t)(dummy); + DMA_InitStructure.DMA_MemoryInc = rx_buffer ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + + DMA_Init(MAX7456_DMA_CHANNEL_RX, &DMA_InitStructure); + DMA_Cmd(MAX7456_DMA_CHANNEL_RX, ENABLE); +#endif + // Tx channel + + DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)tx_buffer; //max7456_screen; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; + + DMA_Init(MAX7456_DMA_CHANNEL_TX, &DMA_InitStructure); + DMA_Cmd(MAX7456_DMA_CHANNEL_TX, ENABLE); + +#ifdef MAX7456_DMA_CHANNEL_RX + DMA_ITConfig(MAX7456_DMA_CHANNEL_RX, DMA_IT_TC, ENABLE); +#else + DMA_ITConfig(MAX7456_DMA_CHANNEL_TX, DMA_IT_TC, ENABLE); +#endif + + // Enable SPI TX/RX request + ENABLE_MAX7456; + dma_transaction_in_progress = 1; + + SPI_I2S_DMACmd(MAX7456_SPI_INSTANCE, +#ifdef MAX7456_DMA_CHANNEL_RX + SPI_I2S_DMAReq_Rx | +#endif + SPI_I2S_DMAReq_Tx, ENABLE); +} + +void MAX7456_DMA_IRQ_HANDLER_FUNCTION (void) { + if (DMA_GetFlagStatus(MAX7456_DMA_TC_FLAG)) { +#ifdef MAX7456_DMA_CHANNEL_RX + DMA_Cmd(MAX7456_DMA_CHANNEL_RX, DISABLE); +#else + //Empty RX buffer. RX DMA takes care of it if enabled + while (SPI_I2S_GetFlagStatus(MAX7456_SPI_INSTANCE, SPI_I2S_FLAG_RXNE) == SET) { + MAX7456_SPI_INSTANCE->DR; + } +#endif + DMA_Cmd(MAX7456_DMA_CHANNEL_TX, DISABLE); + + DMA_ClearFlag(MAX7456_DMA_TC_FLAG); + + SPI_I2S_DMACmd(MAX7456_SPI_INSTANCE, +#ifdef MAX7456_DMA_CHANNEL_RX + SPI_I2S_DMAReq_Rx | +#endif + SPI_I2S_DMAReq_Tx, DISABLE); + + DISABLE_MAX7456; + for (uint16_t x = 0; x < max_screen_size; x++) + max7456_screen[x + 3] = MAX7456ADD_DMDI; + dma_transaction_in_progress = 0; + } +} +#endif void max7456_init(uint8_t video_system) { uint8_t max_screen_rows; uint8_t srdata = 0; uint16_t x; - char buf[LINE]; #ifdef MAX7456_SPI_CS_PIN max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN)); @@ -68,7 +159,7 @@ void max7456_init(uint8_t video_system) { IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG); //Minimum spi clock period for max7456 is 100ns (10Mhz) - spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER); + spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_STANDARD_CLOCK); delay(1000); // force soft reset on Max7456 @@ -112,94 +203,73 @@ void max7456_init(uint8_t video_system) { DISABLE_MAX7456; delay(100); + + for (x = 0; x < max_screen_size; x++) + SCREEN_BUFFER[x] = MAX7456_CHAR(0); + +#ifdef MAX7456_DMA_CHANNEL_TX + max7456_screen[0] = (uint16_t)(MAX7456ADD_DMAH | (0 << 8)); + max7456_screen[1] = (uint16_t)(MAX7456ADD_DMAL | (0 << 8)); + max7456_screen[2] = (uint16_t)(MAX7456ADD_DMM | (1 << 8)); + max7456_screen[max_screen_size + 3] = (uint16_t)(MAX7456ADD_DMDI | (0xFF << 8)); + max7456_screen[max_screen_size + 4] = (uint16_t)(MAX7456ADD_DMM | (0 << 8)); + + RCC_AHBPeriphClockCmd(MAX7456_DMA_PERIPH_CLOCK, ENABLE); + NVIC_InitTypeDef NVIC_InitStructure; + + NVIC_InitStructure.NVIC_IRQChannel = MAX7456_DMA_IRQ_HANDLER_ID; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAX7456_DMA); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAX7456_DMA); + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +#endif } // Copy string from ram into screen buffer void max7456_write_string(const char *string, int16_t address) { - char *dest; + MAX7456_CHAR_TYPE *dest; if (address >= 0) - dest = max7456_screen + address; + dest = SCREEN_BUFFER + address; else - dest = max7456_screen + (max_screen_size + address); + dest = SCREEN_BUFFER + (max_screen_size + address); - while(*string && dest < (max7456_screen + max_screen_size)) - *dest++ = *string++; -} - - -// Write the artifical horizon to the screen buffer -void max7456_artificial_horizon(int rollAngle, int pitchAngle, uint8_t show_sidebars) { - uint16_t position = 194; - - if(pitchAngle>AHIPITCHMAX) pitchAngle=AHIPITCHMAX; - if(pitchAngle<-AHIPITCHMAX) pitchAngle=-AHIPITCHMAX; - if(rollAngle>AHIROLLMAX) rollAngle=AHIROLLMAX; - if(rollAngle<-AHIROLLMAX) rollAngle=-AHIROLLMAX; - - for(uint8_t X=0; X<=8; X++) { - if (X==4) X=5; - int Y = (rollAngle * (4-X)) / 64; - Y -= pitchAngle / 8; - Y += 41; - if(Y >= 0 && Y <= 81) { - uint16_t pos = position -7 + LINE*(Y/9) + 3 - 4*LINE + X; - max7456_screen[pos] = SYM_AH_BAR9_0+(Y%9); - } - } - max7456_screen[position-1] = SYM_AH_CENTER_LINE; - max7456_screen[position+1] = SYM_AH_CENTER_LINE_RIGHT; - max7456_screen[position] = SYM_AH_CENTER; - - if (show_sidebars) { - // Draw AH sides - int8_t hudwidth = AHISIDEBARWIDTHPOSITION; - int8_t hudheight = AHISIDEBARHEIGHTPOSITION; - for(int8_t X=-hudheight; X<=hudheight; X++) { - max7456_screen[position-hudwidth+(X*LINE)] = SYM_AH_DECORATION; - max7456_screen[position+hudwidth+(X*LINE)] = SYM_AH_DECORATION; - } - // AH level indicators - max7456_screen[position-hudwidth+1] = SYM_AH_LEFT; - max7456_screen[position+hudwidth-1] = SYM_AH_RIGHT; + while(*string && dest < (SCREEN_BUFFER + max_screen_size)) { + *dest++ = MAX7456_CHAR(*string++); } } void max7456_draw_screen(void) { - uint16_t xx; if (!max7456_lock) { - ENABLE_MAX7456; - for (xx = 0; xx < max_screen_size; ++xx) { - max7456_send(MAX7456ADD_DMAH, xx>>8); - max7456_send(MAX7456ADD_DMAL, xx); - max7456_send(MAX7456ADD_DMDI, max7456_screen[xx]); - max7456_screen[xx] = ' '; - } - DISABLE_MAX7456; - } -} +#ifdef MAX7456_DMA_CHANNEL_TX + max7456_send_dma(max7456_screen, NULL, max_screen_size * 2 + 10); +#else + uint16_t xx; + max7456_lock = 1; -void max7456_draw_screen_fast(void) { - uint16_t xx; - if (!max7456_lock) { ENABLE_MAX7456; max7456_send(MAX7456ADD_DMAH, 0); max7456_send(MAX7456ADD_DMAL, 0); max7456_send(MAX7456ADD_DMM, 1); for (xx = 0; xx < max_screen_size; ++xx) { - max7456_send(MAX7456ADD_DMDI, max7456_screen[xx]); - max7456_screen[xx] = ' '; + max7456_send(MAX7456ADD_DMDI, SCREEN_BUFFER[xx]); + SCREEN_BUFFER[xx] = MAX7456_CHAR(0); } max7456_send(MAX7456ADD_DMDI, 0xFF); max7456_send(MAX7456ADD_DMM, 0); DISABLE_MAX7456; + max7456_lock = 0; +#endif } } - void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) { uint8_t x; +#ifdef MAX7456_DMA_CHANNEL_TX + while (dma_transaction_in_progress); +#endif + while (max7456_lock); max7456_lock = 1; ENABLE_MAX7456; diff --git a/src/main/drivers/max7456.h b/src/main/drivers/max7456.h index 1e04320a88..5ba902ba5a 100644 --- a/src/main/drivers/max7456.h +++ b/src/main/drivers/max7456.h @@ -143,12 +143,18 @@ enum VIDEO_TYPES { AUTO = 0, PAL, NTSC }; extern uint16_t max_screen_size; -extern char max7456_screen[VIDEO_BUFFER_CHARS_PAL]; +#ifdef MAX7456_DMA_CHANNEL_TX + #define MAX7456_CHAR_TYPE uint16_t + #define MAX7456_CHAR(X) (MAX7456ADD_DMDI | ((X) << 8)) +#else + #define MAX7456_CHAR_TYPE char + #define MAX7456_CHAR(X) (X) +#endif void max7456_init(uint8_t system); void max7456_draw_screen(void); -void max7456_draw_screen_fast(void); -void max7456_artificial_horizon(int rollAngle, int pitchAngle, uint8_t show_sidebars); void max7456_write_string(const char *string, int16_t address); void max7456_write_nvm(uint8_t char_address, uint8_t *font_data); +MAX7456_CHAR_TYPE* max7456_get_screen_buffer(void); + diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index 7d6b100a94..e87fb6bfad 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -39,6 +39,7 @@ #define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f) #define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f) #define NVIC_PRIO_BST_READ_DATA NVIC_BUILD_PRIORITY(1, 1) +#define NVIC_PRIO_MAX7456_DMA NVIC_BUILD_PRIORITY(3, 0) // utility macros to join/split priority #define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index db4c8ad4e0..909ee931e0 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -122,6 +122,11 @@ #define STICKMIN 10 #define STICKMAX 90 +/** Artificial Horizon limits **/ +#define AHIPITCHMAX 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees +#define AHIROLLMAX 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees +#define AHISIDEBARWIDTHPOSITION 7 +#define AHISIDEBARHEIGHTPOSITION 3 static uint32_t next_osd_update_at = 0; static uint32_t armed_seconds = 0; @@ -194,6 +199,23 @@ void print_vtx_freq(uint16_t pos, uint8_t col) { sprintf(string_buffer, "%d M", vtx_freq[current_vtx_channel]); max7456_write_string(string_buffer, pos); } + +void update_vtx_power(int value_change_direction, uint8_t col) { + UNUSED(col); + if (value_change_direction) { + masterConfig.vtx_power = 0; + } else { + masterConfig.vtx_power = 1; + } + rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power); +} + +void print_vtx_power(uint16_t pos, uint8_t col) { + UNUSED(col); + sprintf(string_buffer, "%s", masterConfig.vtx_power ? "25MW" : "200MW"); + max7456_write_string(string_buffer, pos); +} + #endif void print_pid(uint16_t pos, uint8_t col, int pid_term) { @@ -400,7 +422,7 @@ osd_page_t menu_pages[] = { { .title = "VTX SETTINGS", .cols_number = 1, - .rows_number = 3, + .rows_number = 4, .cols = { { .title = NULL, @@ -422,6 +444,11 @@ osd_page_t menu_pages[] = { .title = "FREQUENCY", .update = NULL, .print = print_vtx_freq + }, + { + .title = "POWER", + .update = update_vtx_power, + .print = print_vtx_power } } }, @@ -628,6 +655,49 @@ void show_menu(void) { max7456_write_string(">", cursor_x + cursor_y * OSD_LINE_LENGTH); } +// Write the artifical horizon to the screen buffer +void osdDrawArtificialHorizon(int rollAngle, int pitchAngle, uint8_t show_sidebars) { + uint16_t position = 194; + MAX7456_CHAR_TYPE *screenBuffer = max7456_get_screen_buffer(); + + if (pitchAngle > AHIPITCHMAX) + pitchAngle = AHIPITCHMAX; + if (pitchAngle < -AHIPITCHMAX) + pitchAngle = -AHIPITCHMAX; + if (rollAngle > AHIROLLMAX) + rollAngle = AHIROLLMAX; + if (rollAngle < -AHIROLLMAX) + rollAngle = -AHIROLLMAX; + + for (uint8_t X = 0; X <= 8; X++) { + if (X == 4) + X = 5; + int Y = (rollAngle * (4 - X)) / 64; + Y -= pitchAngle / 8; + Y += 41; + if (Y >= 0 && Y <= 81) { + uint16_t pos = position - 7 + LINE * (Y / 9) + 3 - 4 * LINE + X; + screenBuffer[pos] = MAX7456_CHAR(SYM_AH_BAR9_0 + (Y % 9)); + } + } + screenBuffer[position - 1] = MAX7456_CHAR(SYM_AH_CENTER_LINE); + screenBuffer[position + 1] = MAX7456_CHAR(SYM_AH_CENTER_LINE_RIGHT); + screenBuffer[position] = MAX7456_CHAR(SYM_AH_CENTER); + + if (show_sidebars) { + // Draw AH sides + int8_t hudwidth = AHISIDEBARWIDTHPOSITION; + int8_t hudheight = AHISIDEBARHEIGHTPOSITION; + for (int8_t X = -hudheight; X <= hudheight; X++) { + screenBuffer[position - hudwidth + (X * LINE)] = MAX7456_CHAR(SYM_AH_DECORATION); + screenBuffer[position + hudwidth + (X * LINE)] = MAX7456_CHAR(SYM_AH_DECORATION); + } + // AH level indicators + screenBuffer[position-hudwidth+1] = MAX7456_CHAR(SYM_AH_LEFT); + screenBuffer[position+hudwidth-1] = MAX7456_CHAR(SYM_AH_RIGHT); + } +} + void updateOsd(void) { static uint8_t skip = 0; @@ -645,86 +715,84 @@ void updateOsd(void) if ( !(skip % 2)) blink = !blink; - if (skip++ & 1) { - if (ARMING_FLAG(ARMED)) { - if (!armed) { - armed = true; - armed_at = now; - in_menu = false; - arming = 5; - } - } else { - if (armed) { - armed = false; - armed_seconds += ((now - armed_at) / 1000000); - } - for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) { - sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); - } - if (!in_menu && sticks[YAW] > STICKMAX && sticks[THROTTLE] > STICKMIN && sticks[THROTTLE] < STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMAX) { - in_menu = true; - cursor_row = 255; - cursor_col = 2; - activating_menu = true; - } - } - if (in_menu) { - show_menu(); - } else { - if (batteryWarningVoltage > vbat && blink && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) { - max7456_write_string("LOW VOLTAGE", masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING]); - } - if (arming && blink && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) { - max7456_write_string("ARMED", masterConfig.osdProfile.item_pos[OSD_ARMED]); - arming--; - } - if (!armed && masterConfig.osdProfile.item_pos[OSD_DISARMED] != -1) { - max7456_write_string("DISARMED", masterConfig.osdProfile.item_pos[OSD_DISARMED]); - } - - if (masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] != -1) { - line[0] = SYM_VOLT; - sprintf(line+1, "%d.%1d", vbat / 10, vbat % 10); - max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE]); - } - if (masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] != -1) { - line[0] = SYM_RSSI; - sprintf(line+1, "%d", rssi / 10); - max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE]); - } - if (masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] != -1) { - line[0] = SYM_THR; - line[1] = SYM_THR1; - sprintf(line+2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); - max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS]); - } - if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) { - if (armed) { - seconds = armed_seconds + ((now-armed_at) / 1000000); - line[0] = SYM_FLY_M; - sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60); - } else { - line[0] = SYM_ON_M; - seconds = now / 1000000; - sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60); - } - max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]); - } - if (masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] != -1) { - print_average_system_load(masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], 0); - } - if (masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] != -1) { - max7456_artificial_horizon(attitude.values.roll, attitude.values.pitch, masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] != -1); - } + if (ARMING_FLAG(ARMED)) { + if (!armed) { + armed = true; + armed_at = now; + in_menu = false; + arming = 5; } } else { - max7456_draw_screen_fast(); + if (armed) { + armed = false; + armed_seconds += ((now - armed_at) / 1000000); + } + for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) { + sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); + } + if (!in_menu && sticks[YAW] > STICKMAX && sticks[THROTTLE] > STICKMIN && sticks[THROTTLE] < STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMAX) { + in_menu = true; + cursor_row = 255; + cursor_col = 2; + activating_menu = true; + } } + if (in_menu) { + show_menu(); + } else { + if (batteryWarningVoltage > vbat && blink && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) { + max7456_write_string("LOW VOLTAGE", masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING]); + } + if (arming && blink && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) { + max7456_write_string("ARMED", masterConfig.osdProfile.item_pos[OSD_ARMED]); + arming--; + } + if (!armed && masterConfig.osdProfile.item_pos[OSD_DISARMED] != -1) { + max7456_write_string("DISARMED", masterConfig.osdProfile.item_pos[OSD_DISARMED]); + } + + if (masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] != -1) { + line[0] = SYM_VOLT; + sprintf(line+1, "%d.%1d", vbat / 10, vbat % 10); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE]); + } + if (masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] != -1) { + line[0] = SYM_RSSI; + sprintf(line+1, "%d", rssi / 10); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE]); + } + if (masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] != -1) { + line[0] = SYM_THR; + line[1] = SYM_THR1; + sprintf(line+2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS]); + } + if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) { + if (armed) { + seconds = armed_seconds + ((now-armed_at) / 1000000); + line[0] = SYM_FLY_M; + sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60); + } else { + line[0] = SYM_ON_M; + seconds = now / 1000000; + sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60); + } + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]); + } + if (masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] != -1) { + print_average_system_load(masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], 0); + } + if (masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] != -1) { + osdDrawArtificialHorizon(attitude.values.roll, attitude.values.pitch, masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] != -1); + } + } + max7456_draw_screen(); } void osdInit(void) { uint16_t x; + MAX7456_CHAR_TYPE* screen_buffer = max7456_get_screen_buffer(); max7456_init(masterConfig.osdProfile.video_system); @@ -732,7 +800,8 @@ void osdInit(void) x = 160; for (int i = 1; i < 5; i++) { for (int j = 3; j < 27; j++) - max7456_screen[i * LINE + j] = (char)x++; + if (x != 255) + screen_buffer[(i * LINE + j)] = MAX7456_CHAR(x++); } sprintf(string_buffer, "BF VERSION: %s", FC_VERSION_STRING); max7456_write_string(string_buffer, LINE06 + 5); diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index c27b1ec689..fbbaf6b7b9 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -112,6 +112,13 @@ #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_DMA_CHANNEL_TX DMA2_Channel2 +#define MAX7456_DMA_CHANNEL_RX DMA2_Channel1 +#define MAX7456_DMA_TC_FLAG DMA2_FLAG_TC1 +#define MAX7456_DMA_PERIPH_CLOCK RCC_AHBPeriph_DMA2 +#define MAX7456_DMA_IRQ_HANDLER_FUNCTION DMA2_Channel1_IRQHandler +#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_Channel1_IRQn + #define USE_RTC6705 #define RTC6705_SPIDATA_PIN PC15 #define RTC6705_SPILE_PIN PC14 From 97fe5afd6c1e7f0c066c71ba3c3da0fb4f4ab2ec Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 27 Jun 2016 19:26:02 +0100 Subject: [PATCH 017/108] Converted tabs to spaces. --- src/main/drivers/accgyro_bma280.c | 8 +- src/main/drivers/accgyro_l3g4200d.c | 8 +- src/main/drivers/accgyro_lsm303dlhc.c | 6 +- src/main/drivers/accgyro_mma845x.c | 8 +- src/main/drivers/accgyro_mpu.c | 36 +- src/main/drivers/accgyro_mpu.h | 12 +- src/main/drivers/accgyro_spi_mpu6000.c | 16 +- src/main/drivers/accgyro_spi_mpu6500.c | 2 +- src/main/drivers/accgyro_spi_mpu9250.c | 64 ++-- src/main/drivers/accgyro_spi_mpu9250.h | 2 +- src/main/drivers/adc.c | 10 +- src/main/drivers/adc_stm32f10x.c | 6 +- src/main/drivers/adc_stm32f30x.c | 16 +- src/main/drivers/adc_stm32f4xx.c | 26 +- src/main/drivers/barometer_bmp085.c | 18 +- src/main/drivers/barometer_bmp085.h | 4 +- src/main/drivers/barometer_bmp280.c | 10 +- src/main/drivers/barometer_ms5611.c | 12 +- src/main/drivers/bus_i2c_soft.c | 310 +++++++++--------- src/main/drivers/bus_spi.h | 28 +- src/main/drivers/compass_ak8975.c | 24 +- src/main/drivers/compass_hmc5883l.c | 20 +- src/main/drivers/dma_stm32f4xx.c | 2 +- src/main/drivers/inverter.c | 6 +- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/pwm_mapping.h | 14 +- src/main/drivers/pwm_rx.c | 4 +- src/main/drivers/serial_softserial.c | 2 +- src/main/drivers/serial_uart.h | 12 +- src/main/drivers/serial_uart_stm32f4xx.c | 188 +++++------ src/main/drivers/serial_usb_vcp.c | 10 +- src/main/drivers/sonar_hcsr04.c | 6 +- src/main/drivers/sound_beeper.c | 22 +- src/main/drivers/sound_beeper.h | 6 +- src/main/drivers/system.h | 14 +- src/main/drivers/system_stm32f4xx.c | 34 +- src/main/drivers/timer.c | 6 +- src/main/main.c | 14 +- src/main/mw.c | 4 +- .../target/ALIENFLIGHTF3/hardware_revision.c | 4 +- src/main/target/CC3D/target.c | 52 +-- src/main/target/CJMCU/hardware_revision.c | 4 +- src/main/target/COLIBRI_RACE/target.h | 2 +- src/main/target/FURYF3/target.h | 6 +- src/main/target/KISSFC/target.h | 2 +- src/main/target/LUX_RACE/target.c | 12 +- src/main/target/REVO/target.h | 2 +- src/main/target/REVONANO/target.h | 2 +- src/main/target/SPRACINGF3/target.c | 14 +- src/main/target/X_RACERSPI/target.c | 14 +- src/main/target/X_RACERSPI/target.mk | 2 +- src/main/target/ZCOREF3/target.h | 6 +- src/main/telemetry/hott.c | 12 +- src/main/vcpf4/usb_bsp.c | 10 +- src/main/vcpf4/usb_conf.h | 6 +- src/main/vcpf4/usbd_cdc_vcp.h | 2 +- src/main/vcpf4/usbd_desc.c | 6 +- 57 files changed, 575 insertions(+), 575 deletions(-) diff --git a/src/main/drivers/accgyro_bma280.c b/src/main/drivers/accgyro_bma280.c index 866d944e3d..9d0ab92060 100644 --- a/src/main/drivers/accgyro_bma280.c +++ b/src/main/drivers/accgyro_bma280.c @@ -40,7 +40,7 @@ bool bma280Detect(acc_t *acc) bool ack = false; uint8_t sig = 0; - ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig); + ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig); if (!ack || sig != 0xFB) return false; @@ -51,8 +51,8 @@ bool bma280Detect(acc_t *acc) static void bma280Init(acc_t *acc) { - i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range - i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW + i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range + i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW acc->acc_1G = 512 * 8; } @@ -61,7 +61,7 @@ static bool bma280Read(int16_t *accelData) { uint8_t buf[6]; - if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) { + if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) { return false; } diff --git a/src/main/drivers/accgyro_l3g4200d.c b/src/main/drivers/accgyro_l3g4200d.c index 27beb9d63d..33bd2f1f80 100644 --- a/src/main/drivers/accgyro_l3g4200d.c +++ b/src/main/drivers/accgyro_l3g4200d.c @@ -63,7 +63,7 @@ bool l3g4200dDetect(gyro_t *gyro) delay(25); - i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid); + i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid); if (deviceid != L3G4200D_ID) return false; @@ -100,12 +100,12 @@ static void l3g4200dInit(uint8_t lpf) delay(100); - ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS); + ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS); if (!ack) failureMode(FAILURE_ACC_INIT); delay(5); - i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter); + i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter); } // Read 3 gyro values into user-provided buffer. No overrun checking is done. @@ -113,7 +113,7 @@ static bool l3g4200dRead(int16_t *gyroADC) { uint8_t buf[6]; - if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) { + if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) { return false; } diff --git a/src/main/drivers/accgyro_lsm303dlhc.c b/src/main/drivers/accgyro_lsm303dlhc.c index 505764b29a..7a7222d4d6 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.c +++ b/src/main/drivers/accgyro_lsm303dlhc.c @@ -115,15 +115,15 @@ int32_t accelSummedSamples500Hz[3]; void lsm303dlhcAccInit(acc_t *acc) { - i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT); + i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT); delay(100); - i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE); + i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE); delay(10); - i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G); + i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G); delay(100); diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 2687c34b1a..4adbe59ab8 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -89,7 +89,7 @@ bool mma8452Detect(acc_t *acc) bool ack = false; uint8_t sig = 0; - ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig); + ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig); if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE)) return false; @@ -109,9 +109,9 @@ static inline void mma8451ConfigureInterrupt(void) IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? #endif - i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH) - i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver) - i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2 + i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH) + i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver) + i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2 } static void mma8452Init(acc_t *acc) diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 0882581d34..63cb88ecfc 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -228,43 +228,43 @@ void mpuIntExtiHandler(extiCallbackRec_t *cb) void mpuIntExtiInit(void) { - static bool mpuExtiInitDone = false; + static bool mpuExtiInitDone = false; - if (mpuExtiInitDone || !mpuIntExtiConfig) { - return; - } + if (mpuExtiInitDone || !mpuIntExtiConfig) { + return; + } #if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) - IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); - + IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); + #ifdef ENSURE_MPU_DATA_READY_IS_LOW - uint8_t status = IORead(mpuIntIO); - if (status) { - return; - } + uint8_t status = IORead(mpuIntIO); + if (status) { + return; + } #endif - IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI); - IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? + IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI); + IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? - EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler); - EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); - EXTIEnable(mpuIntIO, true); + EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler); + EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); + EXTIEnable(mpuIntIO, true); #endif - mpuExtiInitDone = true; + mpuExtiInitDone = true; } static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data) { - bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data); + bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data); return ack; } static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data) { - bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data); + bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data); return ack; } diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 6dbfcebf6c..15b6ee9429 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -120,12 +120,12 @@ typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data); typedef void(*mpuResetFuncPtr)(void); typedef struct mpuConfiguration_s { - uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each - mpuReadRegisterFunc read; - mpuWriteRegisterFunc write; - mpuReadRegisterFunc slowread; - mpuWriteRegisterFunc verifywrite; - mpuResetFuncPtr reset; + uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each + mpuReadRegisterFunc read; + mpuWriteRegisterFunc write; + mpuReadRegisterFunc slowread; + mpuWriteRegisterFunc verifywrite; + mpuResetFuncPtr reset; } mpuConfiguration_t; extern mpuConfiguration_t mpuConfiguration; diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index 3d58913d0a..cb78ffe102 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -49,12 +49,12 @@ static bool mpuSpi6000InitDone = false; // Bits -#define BIT_SLEEP 0x40 -#define BIT_H_RESET 0x80 -#define BITS_CLKSEL 0x07 -#define MPU_CLK_SEL_PLLGYROX 0x01 -#define MPU_CLK_SEL_PLLGYROZ 0x03 -#define MPU_EXT_SYNC_GYROX 0x02 +#define BIT_SLEEP 0x40 +#define BIT_H_RESET 0x80 +#define BITS_CLKSEL 0x07 +#define MPU_CLK_SEL_PLLGYROX 0x01 +#define MPU_CLK_SEL_PLLGYROZ 0x03 +#define MPU_EXT_SYNC_GYROX 0x02 #define BITS_FS_250DPS 0x00 #define BITS_FS_500DPS 0x08 #define BITS_FS_1000DPS 0x10 @@ -74,9 +74,9 @@ static bool mpuSpi6000InitDone = false; #define BITS_DLPF_CFG_2100HZ_NOLPF 0x07 #define BITS_DLPF_CFG_MASK 0x07 #define BIT_INT_ANYRD_2CLEAR 0x10 -#define BIT_RAW_RDY_EN 0x01 +#define BIT_RAW_RDY_EN 0x01 #define BIT_I2C_IF_DIS 0x10 -#define BIT_INT_STATUS_DATA 0x01 +#define BIT_INT_STATUS_DATA 0x01 #define BIT_GYRO 3 #define BIT_ACC 2 #define BIT_TEMP 1 diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 4df65c19cb..2731797258 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -72,7 +72,7 @@ static void mpu6500SpiInit(void) IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI); IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG); - spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST); hardwareInitialised = true; } diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 2bad53bf35..95c0b3f50f 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -64,7 +64,7 @@ void mpu9250ResetGyro(void) bool mpu9250WriteRegister(uint8_t reg, uint8_t data) { - ENABLE_MPU9250; + ENABLE_MPU9250; delayMicroseconds(1); spiTransferByte(MPU9250_SPI_INSTANCE, reg); spiTransferByte(MPU9250_SPI_INSTANCE, data); @@ -76,7 +76,7 @@ bool mpu9250WriteRegister(uint8_t reg, uint8_t data) bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data) { - ENABLE_MPU9250; + ENABLE_MPU9250; spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length); DISABLE_MPU9250; @@ -86,7 +86,7 @@ bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data) bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data) { - ENABLE_MPU9250; + ENABLE_MPU9250; delayMicroseconds(1); spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length); @@ -98,7 +98,7 @@ bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data) void mpu9250SpiGyroInit(uint8_t lpf) { - (void)(lpf); + (void)(lpf); mpuIntExtiInit(); @@ -126,55 +126,55 @@ void mpu9250SpiAccInit(acc_t *acc) bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) { - uint8_t in; - uint8_t attemptsRemaining = 20; + uint8_t in; + uint8_t attemptsRemaining = 20; - mpu9250WriteRegister(reg, data); - delayMicroseconds(100); + mpu9250WriteRegister(reg, data); + delayMicroseconds(100); do { - mpu9250SlowReadRegister(reg, 1, &in); - if (in == data) { - return true; - } else { - debug[3]++; - mpu9250WriteRegister(reg, data); - delayMicroseconds(100); - } + mpu9250SlowReadRegister(reg, 1, &in); + if (in == data) { + return true; + } else { + debug[3]++; + mpu9250WriteRegister(reg, data); + delayMicroseconds(100); + } } while (attemptsRemaining--); return false; } static void mpu9250AccAndGyroInit(uint8_t lpf) { - if (mpuSpi9250InitDone) { - return; - } + if (mpuSpi9250InitDone) { + return; + } spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); - delay(50); + delay(50); - verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL); + verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL); - verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11 + verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11 if (lpf == 4) { - verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF + verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF } else if (lpf < 4) { - verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF + verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF } else if (lpf > 4) { - verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF + verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF } - verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops + verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops - verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3); - verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN + verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3); + verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN #if defined(USE_MPU_DATA_READY_SIGNAL) - verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. + verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. #endif spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); @@ -191,10 +191,10 @@ bool mpu9250SpiDetect(void) #ifdef MPU9250_CS_PIN mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN)); #endif - IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI); - IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); + IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); do { diff --git a/src/main/drivers/accgyro_spi_mpu9250.h b/src/main/drivers/accgyro_spi_mpu9250.h index 521cefdf28..1af293288b 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.h +++ b/src/main/drivers/accgyro_spi_mpu9250.h @@ -1,7 +1,7 @@ #pragma once -#define mpu9250_CONFIG 0x1A +#define mpu9250_CONFIG 0x1A /* We should probably use these. :) #define BITS_DLPF_CFG_256HZ 0x00 diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index 46f987dfc7..d214b49d35 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -35,11 +35,11 @@ volatile uint16_t adcValues[ADC_CHANNEL_COUNT]; uint8_t adcChannelByTag(ioTag_t ioTag) { - for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) { - if (ioTag == adcTagMap[i].tag) - return adcTagMap[i].channel; - } - return 0; + for (uint8_t i = 0; i < ARRAYLEN(adcTagMap); i++) { + if (ioTag == adcTagMap[i].tag) + return adcTagMap[i].channel; + } + return 0; } uint16_t adcGetChannel(uint8_t channel) diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index b082388fe2..a810ac731b 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -81,7 +81,7 @@ void adcInit(drv_adc_config_t *init) { #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) - UNUSED(init); + UNUSED(init); #endif uint8_t i; @@ -114,7 +114,7 @@ void adcInit(drv_adc_config_t *init) #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; adcConfig[ADC_EXTERNAL1].enabled = true; @@ -125,7 +125,7 @@ void adcInit(drv_adc_config_t *init) #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); + IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; adcConfig[ADC_CURRENT].enabled = true; diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index dc9c98ee51..8c2ccba5ec 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -107,8 +107,8 @@ void adcInit(drv_adc_config_t *init) #ifdef VBAT_ADC_PIN if (init->enableVBat) { - IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount; @@ -120,8 +120,8 @@ void adcInit(drv_adc_config_t *init) #ifdef RSSI_ADC_PIN if (init->enableRSSI) { - IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); adcConfig[ADC_RSSI].dmaIndex = adcChannelCount; @@ -133,8 +133,8 @@ void adcInit(drv_adc_config_t *init) #ifdef CURRENT_METER_ADC_GPIO if (init->enableCurrentMeter) { - IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount; @@ -146,8 +146,8 @@ void adcInit(drv_adc_config_t *init) #ifdef EXTERNAL1_ADC_GPIO if (init->enableExternal1) { - IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount; diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index 90ca22d12a..e4c086a609 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -39,8 +39,8 @@ #endif const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, - //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, + //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } }; /* note these could be packed up for saving space */ @@ -75,13 +75,13 @@ const adcTagMap_t adcTagMap[] = { ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) - return ADCDEV_1; + if (instance == ADC1) + return ADCDEV_1; /* - if (instance == ADC2) // TODO add ADC2 and 3 - return ADCDEV_2; + if (instance == ADC2) // TODO add ADC2 and 3 + return ADCDEV_2; */ - return ADCINVALID; + return ADCINVALID; } void adcInit(drv_adc_config_t *init) @@ -112,7 +112,7 @@ void adcInit(drv_adc_config_t *init) #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL; adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; adcConfig[ADC_EXTERNAL1].enabled = true; @@ -123,7 +123,7 @@ void adcInit(drv_adc_config_t *init) #ifdef RSSI_ADC_PIN if (init->enableRSSI) { IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL; adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; adcConfig[ADC_RSSI].enabled = true; @@ -134,7 +134,7 @@ void adcInit(drv_adc_config_t *init) #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL; adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; adcConfig[ADC_CURRENT].enabled = true; @@ -184,11 +184,11 @@ void adcInit(drv_adc_config_t *init) ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; - ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; - ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None; + ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels; - ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group + ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group ADC_Init(adc.ADCx, &ADC_InitStructure); diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index a746500b56..34a01cd38e 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -45,8 +45,8 @@ static bool isEOCConnected = true; // EXTI14 for BMP085 End of Conversion Interrupt void bmp085_extiHandler(extiCallbackRec_t* cb) { - UNUSED(cb); - isConversionComplete = true; + UNUSED(cb); + isConversionComplete = true; } bool bmp085TestEOCConnected(const bmp085Config_t *config); @@ -184,13 +184,13 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro) delay(20); // datasheet says 10ms, we'll be careful and do 20. - ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ + ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ if (ack) { bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.oversampling_setting = 3; if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */ - i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */ + i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */ bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */ bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */ bmp085_get_cal_param(); /* readout bmp085 calibparam structure */ @@ -277,7 +277,7 @@ static void bmp085_start_ut(void) #if defined(BARO_EOC_GPIO) isConversionComplete = false; #endif - i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE); + i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE); } static void bmp085_get_ut(void) @@ -291,7 +291,7 @@ static void bmp085_get_ut(void) } #endif - i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data); + i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data); bmp085_ut = (data[0] << 8) | data[1]; } @@ -305,7 +305,7 @@ static void bmp085_start_up(void) isConversionComplete = false; #endif - i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data); + i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data); } /** read out up for pressure conversion @@ -323,7 +323,7 @@ static void bmp085_get_up(void) } #endif - i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data); + i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data); bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - bmp085.oversampling_setting); } @@ -343,7 +343,7 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature static void bmp085_get_cal_param(void) { uint8_t data[22]; - i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); + i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); /*parameters AC1-AC6*/ bmp085.cal_param.ac1 = (data[0] << 8) | data[1]; diff --git a/src/main/drivers/barometer_bmp085.h b/src/main/drivers/barometer_bmp085.h index dafb03a819..328bffb134 100644 --- a/src/main/drivers/barometer_bmp085.h +++ b/src/main/drivers/barometer_bmp085.h @@ -18,8 +18,8 @@ #pragma once typedef struct bmp085Config_s { - ioTag_t xclrIO; - ioTag_t eocIO; + ioTag_t xclrIO; + ioTag_t eocIO; } bmp085Config_t; bool bmp085Detect(const bmp085Config_t *config, baro_t *baro); diff --git a/src/main/drivers/barometer_bmp280.c b/src/main/drivers/barometer_bmp280.c index cf7e60a817..6d42458486 100644 --- a/src/main/drivers/barometer_bmp280.c +++ b/src/main/drivers/barometer_bmp280.c @@ -83,14 +83,14 @@ bool bmp280Detect(baro_t *baro) // set oversampling + power mode (forced), and start sampling bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE); #else - i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */ + i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */ if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID) return false; // read calibration - i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal); + i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal); // set oversampling + power mode (forced), and start sampling - i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); + i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); #endif bmp280InitDone = true; @@ -129,7 +129,7 @@ static void bmp280_start_up(void) { // start measurement // set oversampling + power mode (forced), and start sampling - i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); + i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE); } static void bmp280_get_up(void) @@ -137,7 +137,7 @@ static void bmp280_get_up(void) uint8_t data[BMP280_DATA_FRAME_SIZE]; // read data from sensor - i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data); + i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data); bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4)); bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4)); } diff --git a/src/main/drivers/barometer_ms5611.c b/src/main/drivers/barometer_ms5611.c index 577146e2dc..468f86046f 100644 --- a/src/main/drivers/barometer_ms5611.c +++ b/src/main/drivers/barometer_ms5611.c @@ -67,7 +67,7 @@ bool ms5611Detect(baro_t *baro) delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms - ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig); + ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig); if (!ack) return false; @@ -93,14 +93,14 @@ bool ms5611Detect(baro_t *baro) static void ms5611_reset(void) { - i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1); + i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1); delayMicroseconds(2800); } static uint16_t ms5611_prom(int8_t coef_num) { uint8_t rxbuf[2] = { 0, 0 }; - i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command + i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command return rxbuf[0] << 8 | rxbuf[1]; } @@ -137,13 +137,13 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom) static uint32_t ms5611_read_adc(void) { uint8_t rxbuf[3]; - i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC + i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2]; } static void ms5611_start_ut(void) { - i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start! + i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start! } static void ms5611_get_ut(void) @@ -153,7 +153,7 @@ static void ms5611_get_ut(void) static void ms5611_start_up(void) { - i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start! + i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start! } static void ms5611_get_up(void) diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index edf9e6d726..cac5c62211 100644 --- a/src/main/drivers/bus_i2c_soft.c +++ b/src/main/drivers/bus_i2c_soft.c @@ -48,218 +48,218 @@ static volatile uint16_t i2cErrorCount = 0; static void I2C_delay(void) { - volatile int i = 7; - while (i) { - i--; - } + volatile int i = 7; + while (i) { + i--; + } } static bool I2C_Start(void) { - SDA_H; - SCL_H; - I2C_delay(); - if (!SDA_read) { - return false; - } - SDA_L; - I2C_delay(); - if (SDA_read) { - return false; - } - SDA_L; - I2C_delay(); - return true; + SDA_H; + SCL_H; + I2C_delay(); + if (!SDA_read) { + return false; + } + SDA_L; + I2C_delay(); + if (SDA_read) { + return false; + } + SDA_L; + I2C_delay(); + return true; } static void I2C_Stop(void) { - SCL_L; - I2C_delay(); - SDA_L; - I2C_delay(); - SCL_H; - I2C_delay(); - SDA_H; - I2C_delay(); + SCL_L; + I2C_delay(); + SDA_L; + I2C_delay(); + SCL_H; + I2C_delay(); + SDA_H; + I2C_delay(); } static void I2C_Ack(void) { - SCL_L; - I2C_delay(); - SDA_L; - I2C_delay(); - SCL_H; - I2C_delay(); - SCL_L; - I2C_delay(); + SCL_L; + I2C_delay(); + SDA_L; + I2C_delay(); + SCL_H; + I2C_delay(); + SCL_L; + I2C_delay(); } static void I2C_NoAck(void) { - SCL_L; - I2C_delay(); - SDA_H; - I2C_delay(); - SCL_H; - I2C_delay(); - SCL_L; - I2C_delay(); + SCL_L; + I2C_delay(); + SDA_H; + I2C_delay(); + SCL_H; + I2C_delay(); + SCL_L; + I2C_delay(); } static bool I2C_WaitAck(void) { - SCL_L; - I2C_delay(); - SDA_H; - I2C_delay(); - SCL_H; - I2C_delay(); - if (SDA_read) { - SCL_L; - return false; - } - SCL_L; - return true; + SCL_L; + I2C_delay(); + SDA_H; + I2C_delay(); + SCL_H; + I2C_delay(); + if (SDA_read) { + SCL_L; + return false; + } + SCL_L; + return true; } static void I2C_SendByte(uint8_t byte) { - uint8_t i = 8; - while (i--) { - SCL_L; - I2C_delay(); - if (byte & 0x80) { - SDA_H; - } - else { - SDA_L; - } - byte <<= 1; - I2C_delay(); - SCL_H; - I2C_delay(); - } - SCL_L; + uint8_t i = 8; + while (i--) { + SCL_L; + I2C_delay(); + if (byte & 0x80) { + SDA_H; + } + else { + SDA_L; + } + byte <<= 1; + I2C_delay(); + SCL_H; + I2C_delay(); + } + SCL_L; } static uint8_t I2C_ReceiveByte(void) { - uint8_t i = 8; - uint8_t byte = 0; + uint8_t i = 8; + uint8_t byte = 0; - SDA_H; - while (i--) { - byte <<= 1; - SCL_L; - I2C_delay(); - SCL_H; - I2C_delay(); - if (SDA_read) { - byte |= 0x01; - } - } - SCL_L; - return byte; + SDA_H; + while (i--) { + byte <<= 1; + SCL_L; + I2C_delay(); + SCL_H; + I2C_delay(); + if (SDA_read) { + byte |= 0x01; + } + } + SCL_L; + return byte; } void i2cInit(I2CDevice device) { - UNUSED(device); + UNUSED(device); - scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL)); - sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA)); + scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL)); + sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA)); - IOConfigGPIO(scl, IOCFG_OUT_OD); - IOConfigGPIO(sda, IOCFG_OUT_OD); + IOConfigGPIO(scl, IOCFG_OUT_OD); + IOConfigGPIO(sda, IOCFG_OUT_OD); } bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data) { UNUSED(device); - int i; - if (!I2C_Start()) { - i2cErrorCount++; - return false; - } - I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); - if (!I2C_WaitAck()) { - I2C_Stop(); - return false; - } - I2C_SendByte(reg); - I2C_WaitAck(); - for (i = 0; i < len; i++) { - I2C_SendByte(data[i]); - if (!I2C_WaitAck()) { - I2C_Stop(); - i2cErrorCount++; - return false; - } - } - I2C_Stop(); - return true; + int i; + if (!I2C_Start()) { + i2cErrorCount++; + return false; + } + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + for (i = 0; i < len; i++) { + I2C_SendByte(data[i]); + if (!I2C_WaitAck()) { + I2C_Stop(); + i2cErrorCount++; + return false; + } + } + I2C_Stop(); + return true; } bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data) { UNUSED(device); - if (!I2C_Start()) { - return false; - } - I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); - if (!I2C_WaitAck()) { - I2C_Stop(); - i2cErrorCount++; - return false; - } - I2C_SendByte(reg); - I2C_WaitAck(); - I2C_SendByte(data); - I2C_WaitAck(); - I2C_Stop(); - return true; + if (!I2C_Start()) { + return false; + } + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + i2cErrorCount++; + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + I2C_SendByte(data); + I2C_WaitAck(); + I2C_Stop(); + return true; } bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf) { UNUSED(device); - if (!I2C_Start()) { - return false; - } - I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); - if (!I2C_WaitAck()) { - I2C_Stop(); - i2cErrorCount++; - return false; - } - I2C_SendByte(reg); - I2C_WaitAck(); - I2C_Start(); - I2C_SendByte(addr << 1 | I2C_Direction_Receiver); - I2C_WaitAck(); - while (len) { - *buf = I2C_ReceiveByte(); - if (len == 1) { - I2C_NoAck(); - } - else { - I2C_Ack(); - } - buf++; - len--; - } - I2C_Stop(); - return true; + if (!I2C_Start()) { + return false; + } + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + i2cErrorCount++; + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + I2C_Start(); + I2C_SendByte(addr << 1 | I2C_Direction_Receiver); + I2C_WaitAck(); + while (len) { + *buf = I2C_ReceiveByte(); + if (len == 1) { + I2C_NoAck(); + } + else { + I2C_Ack(); + } + buf++; + len--; + } + I2C_Stop(); + return true; } uint16_t i2cGetErrorCounter(void) { - return i2cErrorCount; + return i2cErrorCount; } #endif diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index d408eac2f7..019080d963 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -52,23 +52,23 @@ typedef enum { } SPIClockDivider_e; typedef enum SPIDevice { - SPIINVALID = -1, - SPIDEV_1 = 0, - SPIDEV_2, - SPIDEV_3, - SPIDEV_MAX = SPIDEV_3, + SPIINVALID = -1, + SPIDEV_1 = 0, + SPIDEV_2, + SPIDEV_3, + SPIDEV_MAX = SPIDEV_3, } SPIDevice; typedef struct SPIDevice_s { - SPI_TypeDef *dev; - ioTag_t nss; - ioTag_t sck; - ioTag_t mosi; - ioTag_t miso; - rccPeriphTag_t rcc; - uint8_t af; - volatile uint16_t errorCount; - bool sdcard; + SPI_TypeDef *dev; + ioTag_t nss; + ioTag_t sck; + ioTag_t mosi; + ioTag_t miso; + rccPeriphTag_t rcc; + uint8_t af; + volatile uint16_t errorCount; + bool sdcard; } spiDevice_t; bool spiInit(SPIDevice device); diff --git a/src/main/drivers/compass_ak8975.c b/src/main/drivers/compass_ak8975.c index 386a06e7d8..c35db1d1f6 100644 --- a/src/main/drivers/compass_ak8975.c +++ b/src/main/drivers/compass_ak8975.c @@ -64,7 +64,7 @@ bool ak8975detect(mag_t *mag) bool ack = false; uint8_t sig = 0; - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig); + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig); if (!ack || sig != 'H') // 0x48 / 01001000 / 'H' return false; @@ -86,24 +86,24 @@ void ak8975Init() UNUSED(ack); - ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode + ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode delay(20); - ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode + ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode delay(10); - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values delay(10); - ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading. + ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading. delay(10); // Clear status registers - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status); - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status); + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status); + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status); // Trigger first measurement - ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); + ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); } #define BIT_STATUS1_REG_DATA_READY (1 << 0) @@ -118,13 +118,13 @@ bool ak8975Read(int16_t *magData) uint8_t status; uint8_t buf[6]; - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status); + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status); if (!ack || (status & BIT_STATUS1_REG_DATA_READY) == 0) { return false; } #if 1 // USE_I2C_SINGLE_BYTE_READS - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH #else for (uint8_t i = 0; i < 6; i++) { ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH @@ -134,7 +134,7 @@ bool ak8975Read(int16_t *magData) } #endif - ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status); + ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status); if (!ack) { return false; } @@ -152,6 +152,6 @@ bool ak8975Read(int16_t *magData) magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4; - ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again + ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again return true; } diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index 4e59c375b8..a018ab0f52 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -204,7 +204,7 @@ bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse) hmc5883Config = hmc5883ConfigToUse; - ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig); + ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig); if (!ack || sig != 'H') return false; @@ -241,15 +241,15 @@ void hmc5883lInit(void) } delay(50); - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias // Note that the very first measurement after a gain change maintains the same gain as the previous setting. // The new gain setting is effective from the second measurement and on. - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011) + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011) delay(100); hmc5883lRead(magADC); for (i = 0; i < 10; i++) { // Collect 10 samples - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1); + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1); delay(50); hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed. @@ -267,9 +267,9 @@ void hmc5883lInit(void) } // Apply the negative bias. (Same gain) - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias. + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias. for (i = 0; i < 10; i++) { - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1); + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1); delay(50); hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed. @@ -291,9 +291,9 @@ void hmc5883lInit(void) magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]); // leave test mode - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga - i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga + i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode delay(100); if (!bret) { // Something went wrong so get a best guess @@ -309,7 +309,7 @@ bool hmc5883lRead(int16_t *magData) { uint8_t buf[6]; - bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); + bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); if (!ack) { return false; } diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index 6b49fe6299..fefbae2801 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -32,7 +32,7 @@ static dmaHandlers_t dmaHandlers; void dmaNoOpHandler(DMA_Stream_TypeDef *stream) { - UNUSED(stream); + UNUSED(stream); } void DMA1_Stream2_IRQHandler(void) diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index 82ce8b0994..e0231ddb78 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -31,15 +31,15 @@ static const IO_t pin = DEFIO_IO(INVERTER); void initInverter(void) { - IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT); - IOConfigGPIO(pin, IOCFG_OUT_PP); + IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOConfigGPIO(pin, IOCFG_OUT_PP); inverterSet(false); } void inverterSet(bool on) { - IOWrite(pin, on); + IOWrite(pin, on); } #endif diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 50061fb790..8d332ba56e 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -306,7 +306,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (type == MAP_TO_PPM_INPUT) { #if defined(SPARKY) || defined(ALIENFLIGHTF3) - if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) { + if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) { ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2); } #endif diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 2212153cde..5d577af8e0 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -78,19 +78,19 @@ typedef struct drv_pwm_config_s { } drv_pwm_config_t; enum { - MAP_TO_PPM_INPUT = 1, + MAP_TO_PPM_INPUT = 1, MAP_TO_PWM_INPUT, MAP_TO_MOTOR_OUTPUT, MAP_TO_SERVO_OUTPUT, }; typedef enum { - PWM_PF_NONE = 0, - PWM_PF_MOTOR = (1 << 0), - PWM_PF_SERVO = (1 << 1), - PWM_PF_MOTOR_MODE_BRUSHED = (1 << 2), - PWM_PF_OUTPUT_PROTOCOL_PWM = (1 << 3), - PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4) + PWM_PF_NONE = 0, + PWM_PF_MOTOR = (1 << 0), + PWM_PF_SERVO = (1 << 1), + PWM_PF_MOTOR_MODE_BRUSHED = (1 << 2), + PWM_PF_OUTPUT_PROTOCOL_PWM = (1 << 3), + PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4) } pwmPortFlags_e; enum {PWM_INVERTED = 1}; diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 9452a89eae..856613d2b3 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -339,8 +339,8 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) { - IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT); - IOConfigGPIO(IOGetByTag(pin), mode); + IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT); + IOConfigGPIO(IOGetByTag(pin), mode); } void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index a2ad403b26..da2c032681 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -96,7 +96,7 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) if (state) { IOHi(softSerial->txIO); } else { - IOLo(softSerial->txIO); + IOLo(softSerial->txIO); } } diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index a332edebf7..33dde32167 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -40,13 +40,13 @@ typedef struct { serialPort_t port; #ifdef STM32F4 - DMA_Stream_TypeDef *rxDMAStream; - DMA_Stream_TypeDef *txDMAStream; - uint32_t rxDMAChannel; - uint32_t txDMAChannel; + DMA_Stream_TypeDef *rxDMAStream; + DMA_Stream_TypeDef *txDMAStream; + uint32_t rxDMAChannel; + uint32_t txDMAChannel; #else - DMA_Channel_TypeDef *rxDMAChannel; - DMA_Channel_TypeDef *txDMAChannel; + DMA_Channel_TypeDef *rxDMAChannel; + DMA_Channel_TypeDef *txDMAChannel; #endif uint32_t rxDMAIrq; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 71b112e368..f5bba84699 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -365,22 +365,22 @@ void DMA2_Stream7_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7)) { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); - } - handleUsartTxDma(s); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); - } } // USART1 Rx/Tx IRQ Handler @@ -402,30 +402,30 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio void DMA1_Stream6_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); - } + if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6)) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); + } } void USART2_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); - usartIrqHandler(s); + usartIrqHandler(s); } #endif @@ -442,22 +442,22 @@ void DMA1_Stream3_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF3)) { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3); - } - handleUsartTxDma(s); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3); } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3); - } } void USART3_IRQHandler(void) @@ -480,22 +480,22 @@ void DMA1_Stream4_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF4)) { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4); - } - handleUsartTxDma(s); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4); } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4); - } } void UART4_IRQHandler(void) @@ -518,22 +518,22 @@ void DMA1_Stream7_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7)) { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); - } - handleUsartTxDma(s); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); - } } void UART5_IRQHandler(void) @@ -556,22 +556,22 @@ void DMA2_Stream6_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6)) { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); - } - handleUsartTxDma(s); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); + } + handleUsartTxDma(s); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); + } + if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) + { + DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); - } } void USART6_IRQHandler(void) diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index e9ccef82fb..bb74b36b3d 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -183,12 +183,12 @@ serialPort_t *usbVcpOpen(void) #ifdef STM32F4 IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO); IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO); - USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); + USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); #else - Set_System(); - Set_USBClock(); - USB_Interrupts_Config(); - USB_Init(); + Set_System(); + Set_USBClock(); + USB_Interrupts_Config(); + USB_Init(); #endif s = &vcpPort; diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 6374f81d3f..3b8ec91f7e 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -92,9 +92,9 @@ void hcsr04_init(sonarRange_t *sonarRange) IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); #ifdef USE_EXTI - EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler); - EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority! - EXTIEnable(echoIO, true); + EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler); + EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority! + EXTIEnable(echoIO, true); #endif lastMeasurementAt = millis() - 60; // force 1st measurement in hcsr04_get_distance() diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index 1e71845d20..cba9a2a5c4 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -39,31 +39,31 @@ static bool beeperInverted = false; void systemBeep(bool onoff) { #ifndef BEEPER - UNUSED(onoff); + UNUSED(onoff); #else - IOWrite(beeperIO, beeperInverted ? onoff : !onoff); + IOWrite(beeperIO, beeperInverted ? onoff : !onoff); #endif } void systemBeepToggle(void) { #ifdef BEEPER - IOToggle(beeperIO); + IOToggle(beeperIO); #endif } void beeperInit(const beeperConfig_t *config) { #ifndef BEEPER - UNUSED(config); + UNUSED(config); #else - beeperIO = IOGetByTag(config->ioTag); - beeperInverted = config->isInverted; + beeperIO = IOGetByTag(config->ioTag); + beeperInverted = config->isInverted; - if (beeperIO) { - IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT); - IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); - } - systemBeep(false); + if (beeperIO) { + IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT); + IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); + } + systemBeep(false); #endif } diff --git a/src/main/drivers/sound_beeper.h b/src/main/drivers/sound_beeper.h index bdd17b7454..ab7a7c3dfc 100644 --- a/src/main/drivers/sound_beeper.h +++ b/src/main/drivers/sound_beeper.h @@ -30,9 +30,9 @@ #endif typedef struct beeperConfig_s { - ioTag_t ioTag; - unsigned isInverted : 1; - unsigned isOD : 1; + ioTag_t ioTag; + unsigned isInverted : 1; + unsigned isOD : 1; } beeperConfig_t; void systemBeep(bool on); diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 6f8bf23d6e..92e17f8a82 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -25,13 +25,13 @@ uint32_t micros(void); uint32_t millis(void); typedef enum { - FAILURE_DEVELOPER = 0, - FAILURE_MISSING_ACC, - FAILURE_ACC_INIT, - FAILURE_ACC_INCOMPATIBLE, - FAILURE_INVALID_EEPROM_CONTENTS, - FAILURE_FLASH_WRITE_FAILED, - FAILURE_GYRO_INIT_FAILED + FAILURE_DEVELOPER = 0, + FAILURE_MISSING_ACC, + FAILURE_ACC_INIT, + FAILURE_ACC_INCOMPATIBLE, + FAILURE_INVALID_EEPROM_CONTENTS, + FAILURE_FLASH_WRITE_FAILED, + FAILURE_GYRO_INIT_FAILED } failureMode_e; // failure diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index bcaf71c9d0..f0042026f9 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -45,8 +45,8 @@ void systemReset(void) if (mpuConfiguration.reset) mpuConfiguration.reset(); - __disable_irq(); - NVIC_SystemReset(); + __disable_irq(); + NVIC_SystemReset(); } void systemResetToBootloader(void) @@ -54,10 +54,10 @@ void systemResetToBootloader(void) if (mpuConfiguration.reset) mpuConfiguration.reset(); - *((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX + *((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX - __disable_irq(); - NVIC_SystemReset(); + __disable_irq(); + NVIC_SystemReset(); } void enableGPIOPowerUsageAndNoiseReductions(void) @@ -82,7 +82,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void) RCC_AHB1Periph_BKPSRAM | RCC_AHB1Periph_DMA1 | RCC_AHB1Periph_DMA2 | - 0, ENABLE + 0, ENABLE ); RCC_AHB2PeriphClockCmd(0, ENABLE); @@ -172,25 +172,25 @@ void systemInit(void) SetSysClock(); // Configure NVIC preempt/priority groups - NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING); + NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING); // cache RCC->CSR value to use it in isMPUSoftreset() and others - cachedRccCsrValue = RCC->CSR; + cachedRccCsrValue = RCC->CSR; /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ - extern void *isr_vector_table_base; - NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); - RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); + extern void *isr_vector_table_base; + NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); + RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); - RCC_ClearFlag(); + RCC_ClearFlag(); - enableGPIOPowerUsageAndNoiseReductions(); + enableGPIOPowerUsageAndNoiseReductions(); // Init cycle counter - cycleCounterInit(); + cycleCounterInit(); - memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs)); - // SysTick - SysTick_Config(SystemCoreClock / 1000); + memset(extiHandlerConfigs, 0x00, sizeof(extiHandlerConfigs)); + // SysTick + SysTick_Config(SystemCoreClock / 1000); } diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 673265f545..732fa5f4ae 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -148,7 +148,7 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim) for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) { if (timerDefinitions[i].TIMx == tim) { return timerDefinitions[i].rcc; - } + } } return 0; } @@ -190,7 +190,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz) #else TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; #endif - + TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure); @@ -660,7 +660,7 @@ void timerInit(void) IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction); } #endif - + // initialize timer channel structures for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { timerChannelInfo[i].type = TYPE_FREE; diff --git a/src/main/main.c b/src/main/main.c index dba36d3f43..b1a157c4d5 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -488,12 +488,12 @@ void init(void) #endif if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, - masterConfig.acc_hardware, - masterConfig.mag_hardware, - masterConfig.baro_hardware, - masterConfig.mag_declination, - masterConfig.gyro_lpf, - masterConfig.gyro_sync_denom)) { + masterConfig.acc_hardware, + masterConfig.mag_hardware, + masterConfig.baro_hardware, + masterConfig.mag_declination, + masterConfig.gyro_lpf, + masterConfig.gyro_sync_denom)) { // if gyro was not detected due to whatever reason, we give up now. failureMode(FAILURE_MISSING_ACC); } @@ -688,7 +688,7 @@ void processLoopback(void) { #define processLoopback() #endif -void main_init(void) +void main_init(void) { init(); diff --git a/src/main/mw.c b/src/main/mw.c index e2819b722c..f77c426733 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -185,7 +185,7 @@ float calculateRate(int axis, int16_t rc) { } - return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection + return constrainf(angleRate, -8190.0f, 8190.0f); // Rate limit protection } void processRcCommand(void) @@ -778,7 +778,7 @@ void subTaskMotorUpdate(void) uint8_t setPidUpdateCountDown(void) { if (masterConfig.gyro_soft_lpf_hz) { - return masterConfig.pid_process_denom - 1; + return masterConfig.pid_process_denom - 1; } else { return 1; } diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c index 2108369958..b51d38658f 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.c +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c @@ -39,7 +39,7 @@ static IO_t HWDetectPin = IO_NONE; void detectHardwareRevision(void) { - HWDetectPin = IOGetByTag(IO_TAG(HW_PIN)); + HWDetectPin = IOGetByTag(IO_TAG(HW_PIN)); IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT); IOConfigGPIO(HWDetectPin, IOCFG_IPU); @@ -74,4 +74,4 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) else { return &alienFlightF3V2MPUIntExtiConfig; } -} \ No newline at end of file +} diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index b146e6a72b..abfe089aa9 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -28,12 +28,12 @@ const uint16_t multiPWM[] = { PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 0xFFFF }; @@ -59,26 +59,26 @@ const uint16_t airPWM[] = { PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 - PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 - PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 0xFFFF }; const uint16_t multiPPM_BP6[] = { PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; @@ -89,9 +89,9 @@ const uint16_t multiPWM_BP6[] = { PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), 0xFFFF @@ -118,11 +118,11 @@ const uint16_t airPWM_BP6[] = { PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8), // input #6 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 - PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 0xFFFF }; diff --git a/src/main/target/CJMCU/hardware_revision.c b/src/main/target/CJMCU/hardware_revision.c index 29071314b8..558e19a760 100755 --- a/src/main/target/CJMCU/hardware_revision.c +++ b/src/main/target/CJMCU/hardware_revision.c @@ -55,5 +55,5 @@ void updateHardwareRevision(void) const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) { - return NULL; -} \ No newline at end of file + return NULL; +} diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 68bf284483..976b287a05 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -34,7 +34,7 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define MPU6000_CS_PIN PA4 +#define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 #define USE_SPI diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 6201b8b3f0..f849070b7d 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -25,9 +25,9 @@ #define USE_EXTI #define CONFIG_PREFER_ACC_ON -#define LED0 PC14 +#define LED0 PC14 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect @@ -188,7 +188,7 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTF (BIT(4)) +#define TARGET_IO_PORTF (BIT(4)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 03c3cf31f6..6d79046a74 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -86,6 +86,6 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTF (BIT(4)) +#define TARGET_IO_PORTF (BIT(4)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index 30804c5754..b665072acf 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -26,12 +26,12 @@ const uint16_t multiPWM[] = { PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index cda67742e6..d2124e5b28 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -23,7 +23,7 @@ #define USBD_PRODUCT_STRING "Revolution" #ifdef OPBL - #define USBD_SERIALNUMBER_STRING "0x8020000" +#define USBD_SERIALNUMBER_STRING "0x8020000" #endif #define LED0 PB5 diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 3c0287f2f7..6f4a2c4315 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -22,7 +22,7 @@ #define USBD_PRODUCT_STRING "Revo Nano" #ifdef OPBL - #define USBD_SERIALNUMBER_STRING "0x8010000" +#define USBD_SERIALNUMBER_STRING "0x8010000" #endif #define LED0 PC14 diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index ff9c8044f8..ddebee117f 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -92,15 +92,15 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index ff9c8044f8..ddebee117f 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -92,15 +92,15 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/X_RACERSPI/target.mk b/src/main/target/X_RACERSPI/target.mk index c0c219bd30..3d831edc43 100644 --- a/src/main/target/X_RACERSPI/target.mk +++ b/src/main/target/X_RACERSPI/target.mk @@ -12,5 +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/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index c02b4d3ecb..d8ac143e88 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -21,7 +21,7 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define LED0 PB8 +#define LED0 PB8 #define BEEPER PC15 #define BEEPER_INVERTED @@ -45,8 +45,8 @@ #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW180_DEG -#define GYRO_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG #define BARO #define USE_BARO_BMP280 diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 1eec8b9c06..6fb0bc1a92 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -424,8 +424,8 @@ static void hottCheckSerialData(uint32_t currentMicros) } static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_t mode) { - closeSerialPort(hottPort); - hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, SERIAL_NOT_INVERTED); + closeSerialPort(hottPort); + hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, SERIAL_NOT_INVERTED); } static void hottSendTelemetryData(void) { @@ -433,9 +433,9 @@ static void hottSendTelemetryData(void) { hottIsSending = true; // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3)) - workAroundForHottTelemetryOnUsart(hottPort, MODE_TX); + workAroundForHottTelemetryOnUsart(hottPort, MODE_TX); else - serialSetMode(hottPort, MODE_TX); + serialSetMode(hottPort, MODE_TX); hottMsgCrc = 0; return; } @@ -445,9 +445,9 @@ static void hottSendTelemetryData(void) { hottIsSending = false; // FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3)) - workAroundForHottTelemetryOnUsart(hottPort, MODE_RX); + workAroundForHottTelemetryOnUsart(hottPort, MODE_RX); else - serialSetMode(hottPort, MODE_RX); + serialSetMode(hottPort, MODE_RX); flushHottRxBuffer(); return; } diff --git a/src/main/vcpf4/usb_bsp.c b/src/main/vcpf4/usb_bsp.c index ba3fee7677..1160c47d8a 100644 --- a/src/main/vcpf4/usb_bsp.c +++ b/src/main/vcpf4/usb_bsp.c @@ -28,12 +28,12 @@ #include "../drivers/io.h" void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev) { - (void)pdev; + (void)pdev; } void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) { - (void)pdev; - (void)state; + (void)pdev; + (void)state; } @@ -46,7 +46,7 @@ void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state) { void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) { - (void)pdev; + (void)pdev; GPIO_InitTypeDef GPIO_InitStructure; #ifndef USE_ULPI_PHY @@ -100,7 +100,7 @@ void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) */ void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev) { - (void)pdev; + (void)pdev; NVIC_InitTypeDef NVIC_InitStructure; NVIC_PriorityGroupConfig(NVIC_PRIORITY_GROUPING); diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h index 6caf298889..60c8036202 100644 --- a/src/main/vcpf4/usb_conf.h +++ b/src/main/vcpf4/usb_conf.h @@ -233,9 +233,9 @@ #elif defined (__ICCARM__) /* IAR Compiler */ #define __packed __packed #elif defined ( __GNUC__ ) /* GNU Compiler */ - #ifndef __packed - #define __packed __attribute__ ((__packed__)) - #endif + #ifndef __packed + #define __packed __attribute__ ((__packed__)) + #endif #elif defined (__TASKING__) /* TASKING Compiler */ #define __packed __unaligned #endif /* __CC_ARM */ diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index 3c89b5b9e8..3ca22aa4ef 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -34,7 +34,7 @@ #include "usbd_usr.h" #include "usbd_desc.h" -#define USB_RX_BUFSIZE 1024 +#define USB_RX_BUFSIZE 1024 __ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END; diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index 41282dab25..f9478327e6 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -197,7 +197,7 @@ __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = */ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length) { - (void)speed; + (void)speed; *length = sizeof(USBD_DeviceDesc); return USBD_DeviceDesc; } @@ -211,7 +211,7 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) { - (void)speed; + (void)speed; *length = sizeof(USBD_LangIDDesc); return USBD_LangIDDesc; } @@ -245,7 +245,7 @@ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length) { - (void)speed; + (void)speed; USBD_GetString ((uint8_t*)USBD_MANUFACTURER_STRING, USBD_StrDesc, length); return USBD_StrDesc; } From 7d5c8de5520b5d177f683a415be42318e4600878 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 27 Jun 2016 19:32:41 +0100 Subject: [PATCH 018/108] Changed tabs to spaces --- src/main/drivers/accgyro_l3gd20.c | 2 +- src/main/drivers/accgyro_spi_mpu6000.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/accgyro_l3gd20.c b/src/main/drivers/accgyro_l3gd20.c index dd28aceb11..aade7445b2 100644 --- a/src/main/drivers/accgyro_l3gd20.c +++ b/src/main/drivers/accgyro_l3gd20.c @@ -62,7 +62,7 @@ #define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00) -#define BLE_MSB ((uint8_t)0x40) +#define BLE_MSB ((uint8_t)0x40) #define BOOT ((uint8_t)0x80) diff --git a/src/main/drivers/accgyro_spi_mpu6000.h b/src/main/drivers/accgyro_spi_mpu6000.h index c717a7bb16..0081bddebb 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.h +++ b/src/main/drivers/accgyro_spi_mpu6000.h @@ -1,7 +1,7 @@ #pragma once -#define MPU6000_CONFIG 0x1A +#define MPU6000_CONFIG 0x1A #define BITS_DLPF_CFG_256HZ 0x00 #define BITS_DLPF_CFG_188HZ 0x01 From a2d1af04aafa5c23b105aad894deb3e6cc787da4 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 27 Jun 2016 20:04:21 +0100 Subject: [PATCH 019/108] Minor cosmetic tidying --- src/main/drivers/timer.c | 2 -- src/main/main.c | 9 ++++----- src/main/sensors/acceleration.c | 2 +- src/main/sensors/barometer.c | 7 ++++--- src/main/sensors/compass.c | 9 +++++---- src/main/target/X_RACERSPI/target.c | 1 - src/main/target/X_RACERSPI/target.h | 2 +- 7 files changed, 15 insertions(+), 17 deletions(-) diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 732fa5f4ae..6999a9798e 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -17,7 +17,6 @@ #include #include -#include #include #include "platform.h" @@ -26,7 +25,6 @@ #include "nvic.h" -#include "gpio.h" #include "gpio.h" #include "rcc.h" #include "system.h" diff --git a/src/main/main.c b/src/main/main.c index b1a157c4d5..e31c6933df 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -17,11 +17,11 @@ #include #include -#include #include #include #include "platform.h" + #include "common/axis.h" #include "common/color.h" #include "common/maths.h" @@ -153,9 +153,6 @@ static uint8_t systemState = SYSTEM_STATE_INITIALISING; void init(void) { - uint8_t i; - drv_pwm_config_t pwm_params; - printfSupportInit(); initEEPROM(); @@ -260,6 +257,7 @@ void init(void) mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer); #endif + drv_pwm_config_t pwm_params; memset(&pwm_params, 0, sizeof(pwm_params)); #ifdef SONAR @@ -333,6 +331,7 @@ void init(void) #endif pwmRxInit(masterConfig.inputFilteringMode); + // pwmInit() needs to be called as soon as possible for ESC compatibility reasons pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params); mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); @@ -504,7 +503,7 @@ void init(void) LED0_OFF; LED2_OFF; - for (i = 0; i < 10; i++) { + for (int i = 0; i < 10; i++) { LED1_TOGGLE; LED0_TOGGLE; delay(25); diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 320d00ddde..1a4f6ef219 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -45,7 +45,7 @@ acc_t acc; // acc access functions sensor_align_e accAlign = 0; uint32_t accTargetLooptime; -uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. +static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. extern uint16_t InflightcalibratingA; extern bool AccInflightCalibrationArmed; diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 2a011d8e2b..1793e37948 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -20,6 +20,10 @@ #include #include "platform.h" + +int32_t BaroAlt = 0; + +#ifdef BARO #include "common/maths.h" #include "drivers/barometer.h" @@ -32,9 +36,6 @@ baro_t baro; // barometer access functions uint16_t calibratingB = 0; // baro calibration = get new ground pressure value int32_t baroPressure = 0; int32_t baroTemperature = 0; -int32_t BaroAlt = 0; - -#ifdef BARO static int32_t baroGroundAltitude = 0; static int32_t baroGroundPressure = 0; diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 7ee14da4c7..de075bfe23 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -40,13 +40,14 @@ #endif mag_t mag; // mag access functions +int32_t magADC[XYZ_AXIS_COUNT]; +sensor_align_e magAlign = 0; + +#ifdef MAG extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead. -int16_t magADCRaw[XYZ_AXIS_COUNT]; -int32_t magADC[XYZ_AXIS_COUNT]; -sensor_align_e magAlign = 0; -#ifdef MAG +static int16_t magADCRaw[XYZ_AXIS_COUNT]; static uint8_t magInit = 0; void compassInit(void) diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index ddebee117f..9c0bd04034 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -84,7 +84,6 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // 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, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index a655c93e25..39c2e6c209 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -17,7 +17,7 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "X_RACERSPI" +#define TARGET_BOARD_IDENTIFIER "XRC3" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE From abd6b1e0f67637c64c053e415920640009a8b6b0 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 28 Jun 2016 07:25:02 +1000 Subject: [PATCH 020/108] Enable pull ups for i2c for F3 targets by default. --- src/main/drivers/bus_i2c_stm32f30x.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index c324d03e7a..adb424390b 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -83,8 +83,8 @@ void i2cInit(I2CDevice device) RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); - IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); - IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4); + IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4); + IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4); I2C_InitTypeDef i2cInit = { .I2C_Mode = I2C_Mode_I2C, From 6068d5daba29e2e62c87318be97649952b6f122e Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Mon, 27 Jun 2016 15:31:48 -0700 Subject: [PATCH 021/108] Fix blinking --- src/main/io/osd.c | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 909ee931e0..a508c66bd8 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -700,8 +700,7 @@ void osdDrawArtificialHorizon(int rollAngle, int pitchAngle, uint8_t show_sideba void updateOsd(void) { - static uint8_t skip = 0; - static bool blink = false; + static uint8_t blink = 0; static uint8_t arming = 0; uint32_t seconds; char line[30]; @@ -712,8 +711,7 @@ void updateOsd(void) return; } next_osd_update_at = now + OSD_UPDATE_FREQUENCY; - if ( !(skip % 2)) - blink = !blink; + blink++; if (ARMING_FLAG(ARMED)) { if (!armed) { @@ -740,10 +738,10 @@ void updateOsd(void) if (in_menu) { show_menu(); } else { - if (batteryWarningVoltage > vbat && blink && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) { + if (batteryWarningVoltage > vbat && (blink & 1) && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) { max7456_write_string("LOW VOLTAGE", masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING]); } - if (arming && blink && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) { + if (arming && (blink & 1) && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) { max7456_write_string("ARMED", masterConfig.osdProfile.item_pos[OSD_ARMED]); arming--; } From 5a10e75551f56597c1ac4aa0ec28d10cf8d127fe Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 28 Jun 2016 10:27:26 +1000 Subject: [PATCH 022/108] Update hmc5883l to use new IO --- src/main/drivers/compass_hmc5883l.c | 81 ++++++----------------------- src/main/drivers/compass_hmc5883l.h | 16 ++---- src/main/sensors/initialisation.c | 31 ++--------- src/main/target/NAZE/target.h | 3 +- src/main/target/SPRACINGF3/target.h | 9 ++-- 5 files changed, 31 insertions(+), 109 deletions(-) diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index a018ab0f52..c8c398fc3d 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -29,7 +29,8 @@ #include "system.h" #include "nvic.h" -#include "gpio.h" +#include "io.h" +#include "exti.h" #include "bus_i2c.h" #include "light_led.h" @@ -120,14 +121,14 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f }; static const hmc5883Config_t *hmc5883Config = NULL; -void MAG_DATA_READY_EXTI_Handler(void) +#ifdef USE_MAG_DATA_READY_SIGNAL + +static IO_t intIO; +static extiCallbackRec_t hmc5883_extiCallbackRec; + +void hmc5883_extiHandler(extiCallbackRec_t* cb) { - if (EXTI_GetITStatus(hmc5883Config->exti_line) == RESET) { - return; - } - - EXTI_ClearITPendingBit(hmc5883Config->exti_line); - + UNUSED(cb); #ifdef DEBUG_MAG_DATA_READY_INTERRUPT // Measure the delta between calls to the interrupt handler // currently should be around 65/66 milli seconds / 15hz output rate @@ -143,57 +144,26 @@ void MAG_DATA_READY_EXTI_Handler(void) lastCalledAt = now; #endif } +#endif static void hmc5883lConfigureDataReadyInterruptHandling(void) { #ifdef USE_MAG_DATA_READY_SIGNAL - if (!(hmc5883Config->exti_port_source && hmc5883Config->exti_pin_source)) { + if (!(hmc5883Config->intTag)) { return; } -#ifdef STM32F10X - // enable AFIO for EXTI support - RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); -#endif - -#ifdef STM32F303xC - /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ - RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); -#endif - -#ifdef STM32F10X - gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source); -#endif - -#ifdef STM32F303xC - gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source); -#endif - + intIO = IOGetByTag(hmc5883Config->intTag); #ifdef ENSURE_MAG_DATA_READY_IS_HIGH - uint8_t status = GPIO_ReadInputDataBit(hmc5883Config->gpioPort, hmc5883Config->gpioPin); + uint8_t status = IORead(intIO); if (!status) { return; } #endif - registerExtiCallbackHandler(hmc5883Config->exti_irqn, MAG_DATA_READY_EXTI_Handler); - - EXTI_ClearITPendingBit(hmc5883Config->exti_line); - - EXTI_InitTypeDef EXTIInit; - EXTIInit.EXTI_Line = hmc5883Config->exti_line; - EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt; - EXTIInit.EXTI_Trigger = EXTI_Trigger_Falling; - EXTIInit.EXTI_LineCmd = ENABLE; - EXTI_Init(&EXTIInit); - - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = hmc5883Config->exti_irqn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAG_DATA_READY); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAG_DATA_READY); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler); + EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising); + EXTIEnable(intIO, true); #endif } @@ -221,25 +191,6 @@ void hmc5883lInit(void) int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow. bool bret = true; // Error indicator - gpio_config_t gpio; - - if (hmc5883Config) { -#ifdef STM32F303 - if (hmc5883Config->gpioAHBPeripherals) { - RCC_AHBPeriphClockCmd(hmc5883Config->gpioAHBPeripherals, ENABLE); - } -#endif -#ifdef STM32F10X - if (hmc5883Config->gpioAPB2Peripherals) { - RCC_APB2PeriphClockCmd(hmc5883Config->gpioAPB2Peripherals, ENABLE); - } -#endif - gpio.pin = hmc5883Config->gpioPin; - gpio.speed = Speed_2MHz; - gpio.mode = Mode_IN_FLOATING; - gpioInit(hmc5883Config->gpioPort, &gpio); - } - delay(50); i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias // Note that the very first measurement after a gain change maintains the same gain as the previous setting. diff --git a/src/main/drivers/compass_hmc5883l.h b/src/main/drivers/compass_hmc5883l.h index 53c4c9f3e5..035a2c936f 100644 --- a/src/main/drivers/compass_hmc5883l.h +++ b/src/main/drivers/compass_hmc5883l.h @@ -17,20 +17,10 @@ #pragma once -typedef struct hmc5883Config_s { -#ifdef STM32F303 - uint32_t gpioAHBPeripherals; -#endif -#ifdef STM32F10X - uint32_t gpioAPB2Peripherals; -#endif - uint16_t gpioPin; - GPIO_TypeDef *gpioPort; +#include "io.h" - uint8_t exti_port_source; - uint32_t exti_line; - uint8_t exti_pin_source; - IRQn_Type exti_irqn; +typedef struct hmc5883Config_s { + ioTag_t intTag; } hmc5883Config_t; bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 80d6169518..2d96a0130a 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -484,27 +484,12 @@ static void detectMag(magSensor_e magHardwareToUse) #ifdef USE_MAG_HMC5883 const hmc5883Config_t *hmc5883Config = 0; -#ifdef NAZE +#ifdef NAZE // TODO remove this target specific define static const hmc5883Config_t nazeHmc5883Config_v1_v4 = { - .gpioAPB2Peripherals = RCC_APB2Periph_GPIOB, - .gpioPin = Pin_12, - .gpioPort = GPIOB, - - /* Disabled for v4 needs more work. - .exti_port_source = GPIO_PortSourceGPIOB, - .exti_pin_source = GPIO_PinSource12, - .exti_line = EXTI_Line12, - .exti_irqn = EXTI15_10_IRQn - */ + .intTag = IO_TAG(PB12) /* perhaps disabled? */ }; static const hmc5883Config_t nazeHmc5883Config_v5 = { - .gpioAPB2Peripherals = RCC_APB2Periph_GPIOC, - .gpioPin = Pin_14, - .gpioPort = GPIOC, - .exti_port_source = GPIO_PortSourceGPIOC, - .exti_line = EXTI_Line14, - .exti_pin_source = GPIO_PinSource14, - .exti_irqn = EXTI15_10_IRQn + .intTag = IO_TAG(MAG_INT_EXTI) }; if (hardwareRevision < NAZE32_REV5) { hmc5883Config = &nazeHmc5883Config_v1_v4; @@ -513,15 +498,9 @@ static void detectMag(magSensor_e magHardwareToUse) } #endif -#ifdef SPRACINGF3 +#ifdef MAG_INT_EXTI static const hmc5883Config_t spRacingF3Hmc5883Config = { - .gpioAHBPeripherals = RCC_AHBPeriph_GPIOC, - .gpioPin = Pin_14, - .gpioPort = GPIOC, - .exti_port_source = EXTI_PortSourceGPIOC, - .exti_pin_source = EXTI_PinSource14, - .exti_line = EXTI_Line14, - .exti_irqn = EXTI15_10_IRQn + .intTag = IO_TAG(MAG_INT_EXTI) }; hmc5883Config = &spRacingF3Hmc5883Config; diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 9f6e3d2b22..95f531faf5 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -74,7 +74,8 @@ //#define DEBUG_MAG_DATA_READY_INTERRUPT #define USE_MAG_DATA_READY_SIGNAL - +#define MAG_INT_EXTI PC14 + #define GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 68413bbe0b..a4f44762dc 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -35,10 +35,6 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define USE_MAG_DATA_READY_SIGNAL -#define ENSURE_MAG_DATA_READY_IS_HIGH - - #define GYRO #define USE_GYRO_MPU6050 #define GYRO_MPU6050_ALIGN CW270_DEG @@ -57,6 +53,11 @@ #define USE_MAG_HMC5883 #define MAG_HMC5883_ALIGN CW270_DEG +#define USE_MAG_DATA_READY_SIGNAL +#define ENSURE_MAG_DATA_READY_IS_HIGH +#define MAG_INT_EXTI PC14 + + #define USE_FLASHFS #define USE_FLASH_M25P16 From e04c0a3d66ad5e44b06b23ca8a1b1b2f6cd2ee9f Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 28 Jun 2016 15:13:33 +1000 Subject: [PATCH 023/108] Additional IO cleanup for HMC5883 fix --- src/main/drivers/accgyro_lsm303dlhc.c | 2 +- src/main/drivers/accgyro_lsm303dlhc.h | 57 ++++++--------------------- src/main/drivers/accgyro_mpu.h | 2 + src/main/drivers/compass_ak8963.c | 2 - 4 files changed, 14 insertions(+), 49 deletions(-) diff --git a/src/main/drivers/accgyro_lsm303dlhc.c b/src/main/drivers/accgyro_lsm303dlhc.c index 7a7222d4d6..4caed30911 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.c +++ b/src/main/drivers/accgyro_lsm303dlhc.c @@ -26,7 +26,7 @@ #include "common/axis.h" #include "system.h" -#include "gpio.h" +#include "io.h" #include "bus_i2c.h" #include "sensor.h" diff --git a/src/main/drivers/accgyro_lsm303dlhc.h b/src/main/drivers/accgyro_lsm303dlhc.h index 6cc79066cc..1f5c56f68e 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.h +++ b/src/main/drivers/accgyro_lsm303dlhc.h @@ -22,8 +22,7 @@ */ /* LSM303DLHC ACC struct */ -typedef struct -{ +typedef struct { uint8_t Power_Mode; /* Power-down/Normal Mode */ uint8_t AccOutput_DataRate; /* OUT data rate */ uint8_t Axes_Enable; /* Axes enable */ @@ -31,25 +30,23 @@ typedef struct uint8_t BlockData_Update; /* Block Data Update */ uint8_t Endianness; /* Endian Data selection */ uint8_t AccFull_Scale; /* Full Scale selection */ -}LSM303DLHCAcc_InitTypeDef; +} LSM303DLHCAcc_InitTypeDef; /* LSM303DLHC Acc High Pass Filter struct */ -typedef struct -{ +typedef struct { uint8_t HighPassFilter_Mode_Selection; /* Internal filter mode */ uint8_t HighPassFilter_CutOff_Frequency; /* High pass filter cut-off frequency */ uint8_t HighPassFilter_AOI1; /* HPF_enabling/disabling for AOI function on interrupt 1 */ uint8_t HighPassFilter_AOI2; /* HPF_enabling/disabling for AOI function on interrupt 2 */ -}LSM303DLHCAcc_FilterConfigTypeDef; +} LSM303DLHCAcc_FilterConfigTypeDef; /* LSM303DLHC Mag struct */ -typedef struct -{ +typedef struct { uint8_t Temperature_Sensor; /* Temperature sensor enable/disable */ uint8_t MagOutput_DataRate; /* OUT data rate */ uint8_t Working_Mode; /* operating mode */ uint8_t MagFull_Scale; /* Full Scale selection */ -}LSM303DLHCMag_InitTypeDef; +} LSM303DLHCMag_InitTypeDef; /** * @} */ @@ -78,43 +75,11 @@ typedef struct * @brief LSM303DLHC I2C Interface pins */ #define LSM303DLHC_I2C I2C1 -#define LSM303DLHC_I2C_CLK RCC_APB1Periph_I2C1 - -#define LSM303DLHC_I2C_SCK_PIN GPIO_Pin_6 /* PB.06 */ -#define LSM303DLHC_I2C_SCK_GPIO_PORT GPIOB /* GPIOB */ -#define LSM303DLHC_I2C_SCK_GPIO_CLK RCC_AHBPeriph_GPIOB -#define LSM303DLHC_I2C_SCK_SOURCE GPIO_PinSource6 -#define LSM303DLHC_I2C_SCK_AF GPIO_AF_4 - -#define LSM303DLHC_I2C_SDA_PIN GPIO_Pin_7 /* PB.7 */ -#define LSM303DLHC_I2C_SDA_GPIO_PORT GPIOB /* GPIOB */ -#define LSM303DLHC_I2C_SDA_GPIO_CLK RCC_AHBPeriph_GPIOB -#define LSM303DLHC_I2C_SDA_SOURCE GPIO_PinSource7 -#define LSM303DLHC_I2C_SDA_AF GPIO_AF_4 - -#define LSM303DLHC_DRDY_PIN GPIO_Pin_2 /* PE.02 */ -#define LSM303DLHC_DRDY_GPIO_PORT GPIOE /* GPIOE */ -#define LSM303DLHC_DRDY_GPIO_CLK RCC_AHBPeriph_GPIOE -#define LSM303DLHC_DRDY_EXTI_LINE EXTI_Line2 -#define LSM303DLHC_DRDY_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE -#define LSM303DLHC_DRDY_EXTI_PIN_SOURCE EXTI_PinSource2 -#define LSM303DLHC_DRDY_EXTI_IRQn EXTI2_TS_IRQn - -#define LSM303DLHC_I2C_INT1_PIN GPIO_Pin_4 /* PE.04 */ -#define LSM303DLHC_I2C_INT1_GPIO_PORT GPIOE /* GPIOE */ -#define LSM303DLHC_I2C_INT1_GPIO_CLK RCC_AHBPeriph_GPIOE -#define LSM303DLHC_I2C_INT1_EXTI_LINE EXTI_Line4 -#define LSM303DLHC_I2C_INT1_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE -#define LSM303DLHC_I2C_INT1_EXTI_PIN_SOURCE EXTI_PinSource4 -#define LSM303DLHC_I2C_INT1_EXTI_IRQn EXTI4_IRQn - -#define LSM303DLHC_I2C_INT2_PIN GPIO_Pin_5 /* PE.05 */ -#define LSM303DLHC_I2C_INT2_GPIO_PORT GPIOE /* GPIOE */ -#define LSM303DLHC_I2C_INT2_GPIO_CLK RCC_AHBPeriph_GPIOE -#define LSM303DLHC_I2C_INT2_EXTI_LINE EXTI_Line5 -#define LSM303DLHC_I2C_INT2_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE -#define LSM303DLHC_I2C_INT2_EXTI_PIN_SOURCE EXTI_PinSource5ss -#define LSM303DLHC_I2C_INT2_EXTI_IRQn EXTI9_5_IRQn +#define LSM303DLHC_I2C_SCK_PIN PB6 /* PB.06 */ +#define LSM303DLHC_I2C_SDA_PIN PB7 /* PB.7 */ +#define LSM303DLHC_DRDY_PIN PE2 /* PE.02 */ +#define LSM303DLHC_I2C_INT1_PIN PE4 /* PE.04 */ +#define LSM303DLHC_I2C_INT2_PIN PE5 /* PE.05 */ /******************************************************************************/ /*************************** START REGISTER MAPPING **************************/ diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 4ce6b552de..917c06f1a8 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -17,6 +17,8 @@ #pragma once +#include "exti.h" + // MPU6050 #define MPU_RA_WHO_AM_I 0x75 #define MPU_RA_WHO_AM_I_LEGACY 0x00 diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c index 7b60fe5c46..0668fcdd77 100644 --- a/src/main/drivers/compass_ak8963.c +++ b/src/main/drivers/compass_ak8963.c @@ -30,8 +30,6 @@ #include "common/maths.h" #include "system.h" -#include "gpio.h" -#include "exti.h" #include "bus_i2c.h" #include "bus_spi.h" From 657564efa7907c34fa2e733e47379170189846c4 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 28 Jun 2016 19:47:00 +1000 Subject: [PATCH 024/108] Small tidy --- src/main/drivers/bus_i2c_stm32f30x.c | 8 ++++---- src/main/sensors/compass.c | 2 +- src/main/sensors/initialisation.c | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index adb424390b..1457316672 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -31,6 +31,9 @@ #ifndef SOFT_I2C +#define I2C_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4. +#define I2C_STANDARD_TIMING 0x00E0257A // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. + #define I2C_SHORT_TIMEOUT ((uint32_t)0x1000) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) #define I2C_GPIO_AF GPIO_AF_4 @@ -93,10 +96,7 @@ void i2cInit(I2CDevice device) .I2C_OwnAddress1 = 0x00, .I2C_Ack = I2C_Ack_Enable, .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_Timing = i2c->overClock ? - 0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4. - 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. - //.I2C_Timing = 0x8000050B; + .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING) }; I2C_Init(I2Cx, &i2cInit); diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index de075bfe23..cca2328c04 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -35,7 +35,7 @@ #include "sensors/sensors.h" #include "sensors/compass.h" -#ifdef NAZE +#ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 2d96a0130a..399ad7b842 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -499,11 +499,11 @@ static void detectMag(magSensor_e magHardwareToUse) #endif #ifdef MAG_INT_EXTI - static const hmc5883Config_t spRacingF3Hmc5883Config = { + static const hmc5883Config_t extiHmc5883Config = { .intTag = IO_TAG(MAG_INT_EXTI) }; - hmc5883Config = &spRacingF3Hmc5883Config; + hmc5883Config = &extiHmc5883Config; #endif #endif From c5071fcdad567ee7f20c98c2294e1af8a7b3e3ff Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 28 Jun 2016 21:07:04 +1000 Subject: [PATCH 025/108] USE_I2C_PULLUP now a potential define in target.h --- src/main/drivers/bus_i2c_stm32f30x.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 1457316672..cc78da8d60 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -31,6 +31,12 @@ #ifndef SOFT_I2C +#if defined(USE_I2C_PULLUP) +#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP) +#else +#define IOCFG_I2C IOCFG_AF_OD +#endif + #define I2C_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4. #define I2C_STANDARD_TIMING 0x00E0257A // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10. @@ -86,8 +92,8 @@ void i2cInit(I2CDevice device) RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); - IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4); - IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4); + IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); + IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { .I2C_Mode = I2C_Mode_I2C, From 32d5a664d5a7c5ecd87aa70115e8fb25446fdddd Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 28 Jun 2016 20:46:47 +0100 Subject: [PATCH 026/108] Fixed KISS VBAT and motor order --- src/main/target/KISSFC/target.c | 20 ++++++++++---------- src/main/target/KISSFC/target.h | 10 +++++----- src/main/target/KISSFC/target.mk | 2 +- 3 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index 30d03b9f69..db129454a4 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -7,33 +7,33 @@ const uint16_t multiPPM[] = { PWM7 | (MAP_TO_PPM_INPUT << 8), - PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), 0xFFFF }; const uint16_t multiPWM[] = { - PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM7 | (MAP_TO_PWM_INPUT << 8), PWM8 | (MAP_TO_PWM_INPUT << 8), PWM9 | (MAP_TO_PWM_INPUT << 8), - PWM10 | (MAP_TO_PWM_INPUT << 8), - PWM11 | (MAP_TO_PWM_INPUT << 8), - PWM12 | (MAP_TO_PWM_INPUT << 8), + PWM10 | (MAP_TO_PWM_INPUT << 8), + PWM11 | (MAP_TO_PWM_INPUT << 8), + PWM12 | (MAP_TO_PWM_INPUT << 8), 0xFFFF }; diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 6d79046a74..f45fbe0590 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -72,11 +72,11 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA -//#define USE_ADC -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PA0 +//#define CURRENT_METER_ADC_PIN PA5 +//#define RSSI_ADC_PIN PB2 #define SPEKTRUM_BIND diff --git a/src/main/target/KISSFC/target.mk b/src/main/target/KISSFC/target.mk index 56c635c922..6ed94fd46d 100644 --- a/src/main/target/KISSFC/target.mk +++ b/src/main/target/KISSFC/target.mk @@ -1,5 +1,5 @@ F3_TARGETS += $(TARGET) -FEATURES = VCP +FEATURES = VCP TARGET_SRC = \ drivers/accgyro_mpu.c \ From a4788fa2ab033415e4fb9f603a1877b1ebb8e7d6 Mon Sep 17 00:00:00 2001 From: nathan Date: Mon, 27 Jun 2016 22:22:29 -0700 Subject: [PATCH 027/108] its betaflight, not raceflight :) --- src/main/vcpf4/usbd_desc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index f9478327e6..f3f9a3af91 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -57,7 +57,7 @@ * @{ */ #define USBD_LANGID_STRING 0x409 -#define USBD_MANUFACTURER_STRING "RaceFlight" +#define USBD_MANUFACTURER_STRING "BetaFlight" #ifdef USBD_PRODUCT_STRING #define USBD_PRODUCT_HS_STRING USBD_PRODUCT_STRING From e70d15114b013da8d0bda2150d406ab7392f2f81 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 29 Jun 2016 19:00:18 +1000 Subject: [PATCH 028/108] Fixed ADC issue with NAZE (and other F1 targets) --- src/main/drivers/adc.h | 3 ++ src/main/drivers/adc_stm32f10x.c | 44 +++++++++------------- src/main/drivers/adc_stm32f30x.c | 48 ++++++++---------------- src/main/drivers/adc_stm32f4xx.c | 64 ++++++++++++++------------------ src/main/drivers/rcc.c | 8 ++-- 5 files changed, 68 insertions(+), 99 deletions(-) diff --git a/src/main/drivers/adc.h b/src/main/drivers/adc.h index f090c8fa8d..55914a3365 100644 --- a/src/main/drivers/adc.h +++ b/src/main/drivers/adc.h @@ -17,6 +17,8 @@ #pragma once +#include "io.h" + typedef enum { ADC_BATTERY = 0, ADC_RSSI = 1, @@ -28,6 +30,7 @@ typedef enum { #define ADC_CHANNEL_COUNT (ADC_CHANNEL_MAX + 1) typedef struct adc_config_s { + ioTag_t tag; uint8_t adcChannel; // ADC1_INxx channel number uint8_t dmaIndex; // index into DMA buffer in case of sparse channels bool enabled; diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index a810ac731b..9d94742468 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -91,60 +91,50 @@ void adcInit(drv_adc_config_t *init) #ifdef VBAT_ADC_PIN if (init->enableVBat) { - IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); - adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); - adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_BATTERY].enabled = true; - adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5; + adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { - IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); - adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); - adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_RSSI].enabled = true; - adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5; + adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); } #endif #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { - IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); - adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); - adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_EXTERNAL1].enabled = true; - adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5; + adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { - IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AIN, 0)); - adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); - adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_CURRENT].enabled = true; - adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5; + adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); } #endif ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; - + adcDevice_t adc = adcHardware[device]; + + for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { + if (!adcConfig[i].tag) + continue; + + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); + adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); + adcConfig[i].dmaIndex = configuredAdcChannels++; + adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5; + adcConfig[i].enabled = true; + } RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE); - // FIXME ADC driver assumes all the GPIO was already placed in 'AIN' mode - DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 8c2ccba5ec..3fc7427b5a 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -107,53 +107,25 @@ void adcInit(drv_adc_config_t *init) #ifdef VBAT_ADC_PIN if (init->enableVBat) { - IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - - adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); - adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount; - adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5; - adcConfig[ADC_BATTERY].enabled = true; - adcChannelCount++; + adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { - IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - - adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); - adcConfig[ADC_RSSI].dmaIndex = adcChannelCount; - adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5; - adcConfig[ADC_RSSI].enabled = true; - adcChannelCount++; + adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); } #endif #ifdef CURRENT_METER_ADC_GPIO if (init->enableCurrentMeter) { - IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - - adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); - adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount; - adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5; - adcConfig[ADC_CURRENT].enabled = true; - adcChannelCount++; + adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); } #endif #ifdef EXTERNAL1_ADC_GPIO if (init->enableExternal1) { - IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - - adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); - adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount; - adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5; - adcConfig[ADC_EXTERNAL1].enabled = true; - adcChannelCount++; + adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); } #endif @@ -163,6 +135,18 @@ void adcInit(drv_adc_config_t *init) adcDevice_t adc = adcHardware[device]; + for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { + if (!adcConfig[i].tag) + continue; + + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); + adcConfig[i].dmaIndex = adcChannelCount++; + adcConfig[i].sampleTime = ADC_SampleTime_601Cycles5; + adcConfig[i].enabled = true; + } + RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE); diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index e4c086a609..e0b36a5f33 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -100,45 +100,25 @@ void adcInit(drv_adc_config_t *init) #ifdef VBAT_ADC_PIN if (init->enableVBat) { - IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_BATTERY].adcChannel = adcChannelByTag(IO_TAG(VBAT_ADC_PIN)); //VBAT_ADC_CHANNEL; - adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_BATTERY].enabled = true; - adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles; - } -#endif - -#ifdef EXTERNAL1_ADC_PIN - if (init->enableExternal1) { - IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_EXTERNAL1].adcChannel = adcChannelByTag(IO_TAG(EXTERNAL1_ADC_PIN)); //EXTERNAL1_ADC_CHANNEL; - adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_EXTERNAL1].enabled = true; - adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles; + adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); //VBAT_ADC_CHANNEL; } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { - IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_RSSI].adcChannel = adcChannelByTag(IO_TAG(RSSI_ADC_PIN)); //RSSI_ADC_CHANNEL; - adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_RSSI].enabled = true; - adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles; + adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL; + } +#endif + +#ifdef EXTERNAL1_ADC_PIN + if (init->enableExternal1) { + adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL; } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { - IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); - IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); - adcConfig[ADC_CURRENT].adcChannel = adcChannelByTag(IO_TAG(CURRENT_METER_ADC_PIN)); //CURRENT_METER_ADC_CHANNEL; - adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; - adcConfig[ADC_CURRENT].enabled = true; - adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles; + adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); //CURRENT_METER_ADC_CHANNEL; } #endif @@ -150,6 +130,18 @@ void adcInit(drv_adc_config_t *init) adcDevice_t adc = adcHardware[device]; + for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { + if (!adcConfig[i].tag) + continue; + + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); + adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); + adcConfig[i].dmaIndex = configuredAdcChannels++; + adcConfig[i].sampleTime = ADC_SampleTime_480Cycles; + adcConfig[i].enabled = true; + } + RCC_ClockCmd(adc.rccDMA, ENABLE); RCC_ClockCmd(adc.rccADC, ENABLE); @@ -174,20 +166,20 @@ void adcInit(drv_adc_config_t *init) ADC_CommonInitTypeDef ADC_CommonInitStructure; ADC_CommonStructInit(&ADC_CommonInitStructure); - ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; - ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8; - ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; + ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; + ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8; + ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; ADC_CommonInit(&ADC_CommonInitStructure); ADC_StructInit(&ADC_InitStructure); - ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; - ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; + ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; + ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None; - ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; - ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels; + ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; + ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels; ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group ADC_Init(adc.ADCx, &ADC_InitStructure); diff --git a/src/main/drivers/rcc.c b/src/main/drivers/rcc.c index f8cc88b725..b1e759f972 100644 --- a/src/main/drivers/rcc.c +++ b/src/main/drivers/rcc.c @@ -7,7 +7,7 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) int tag = periphTag >> 5; uint32_t mask = 1 << (periphTag & 0x1f); switch (tag) { -#if defined(STM32F303xC) +#if defined(STM32F3) || defined(STM32F1) case RCC_AHB: RCC_AHBPeriphClockCmd(mask, NewState); break; @@ -18,7 +18,7 @@ void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) case RCC_APB1: RCC_APB1PeriphClockCmd(mask, NewState); break; -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#if defined(STM32F4) case RCC_AHB1: RCC_AHB1PeriphClockCmd(mask, NewState); break; @@ -31,7 +31,7 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState) int tag = periphTag >> 5; uint32_t mask = 1 << (periphTag & 0x1f); switch (tag) { -#if defined(STM32F303xC) +#if defined(STM32F3) || defined(STM32F10X_CL) case RCC_AHB: RCC_AHBPeriphResetCmd(mask, NewState); break; @@ -42,7 +42,7 @@ void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState) case RCC_APB1: RCC_APB1PeriphResetCmd(mask, NewState); break; -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#if defined(STM32F4) case RCC_AHB1: RCC_AHB1PeriphResetCmd(mask, NewState); break; From 72934e2be286e069b1ad9d971c34df4cb195b54d Mon Sep 17 00:00:00 2001 From: nathan Date: Wed, 29 Jun 2016 02:02:57 -0700 Subject: [PATCH 029/108] betaflight font mapping accounts for logo at the end of the font file, starting at 0xA0 --- src/main/drivers/max7456_symbols.h | 21 +++++++-------------- 1 file changed, 7 insertions(+), 14 deletions(-) diff --git a/src/main/drivers/max7456_symbols.h b/src/main/drivers/max7456_symbols.h index 68de428937..2030cb956b 100644 --- a/src/main/drivers/max7456_symbols.h +++ b/src/main/drivers/max7456_symbols.h @@ -125,16 +125,9 @@ #define SYM_MAG11 0xB6 // AH Center screen Graphics -//#define SYM_AH_CENTER 0x01 -#ifdef ALT_CENTER - #define SYM_AH_CENTER_LINE 0xB0 - #define SYM_AH_CENTER 0xB1 - #define SYM_AH_CENTER_LINE_RIGHT 0xB2 -#else - #define SYM_AH_CENTER_LINE 0x26 - #define SYM_AH_CENTER 0x7E - #define SYM_AH_CENTER_LINE_RIGHT 0xBC -#endif +#define SYM_AH_CENTER_LINE 0x26 +#define SYM_AH_CENTER_LINE_RIGHT 0x27 +#define SYM_AH_CENTER 0x7E #define SYM_AH_RIGHT 0x02 #define SYM_AH_LEFT 0x03 #define SYM_AH_DECORATION_UP 0xC9 @@ -183,7 +176,7 @@ #define SYM_FT 0x0F // Voltage and amperage -#define SYM_VOLT 0xA9 +#define SYM_VOLT 0x00 #define SYM_AMP 0x9A #define SYM_MAH 0xA4 #define SYM_WATT 0x57 @@ -214,11 +207,11 @@ #define SYM_FLY_H 0x71 // Throttle Position (%) -#define SYM_THR 0xC8 -#define SYM_THR1 0xC9 +#define SYM_THR 0x04 +#define SYM_THR1 0x05 // RSSI -#define SYM_RSSI 0xBA +#define SYM_RSSI 0x01 // Menu cursor #define SYM_CURSOR SYM_AH_LEFT From 7bf60be27f99713d4431674279102861b96b8e59 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 29 Jun 2016 15:01:45 +0100 Subject: [PATCH 030/108] Configuable default VBAT settings --- src/main/config/config.c | 3 --- src/main/sensors/battery.h | 2 ++ src/main/target/ALIENFLIGHTF3/target.h | 5 ++--- src/main/target/KISSFC/target.h | 3 +++ src/main/target/SINGULARITY/target.h | 1 + 5 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 2c0c9c17d9..284c59097b 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -659,7 +659,6 @@ static void resetConf(void) masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; #endif #ifdef ALIENFLIGHTF3 - masterConfig.batteryConfig.vbatscale = 20; masterConfig.mag_hardware = MAG_NONE; // disabled by default #endif masterConfig.rxConfig.serialrx_provider = SERIALRX_SPEKTRUM2048; @@ -687,8 +686,6 @@ static void resetConf(void) #if defined(SINGULARITY) // alternative defaults settings for SINGULARITY target - masterConfig.batteryConfig.vbatscale = 77; - masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; #endif diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h index 26e54eb4ec..21197e07fc 100644 --- a/src/main/sensors/battery.h +++ b/src/main/sensors/battery.h @@ -20,7 +20,9 @@ #include "rx/rx.h" #include "common/maths.h" +#ifndef VBAT_SCALE_DEFAULT #define VBAT_SCALE_DEFAULT 110 +#endif #define VBAT_RESDIVVAL_DEFAULT 10 #define VBAT_RESDIVMULTIPLIER_DEFAULT 1 #define VBAT_SCALE_MIN 0 diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 89e9c1a9c6..ccef02d34d 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -18,6 +18,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. +#define ALIENFLIGHT #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT @@ -118,9 +119,7 @@ #define ADC_INSTANCE ADC2 //#define BOARD_HAS_VOLTAGE_DIVIDER #define VBAT_ADC_PIN PA4 - -// alternative defaults for AlienFlight F3 target -#define ALIENFLIGHT +#define VBAT_SCALE_DEFAULT 20 #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index f45fbe0590..538dc653b8 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -73,11 +73,14 @@ #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_ADC +#define VBAT_SCALE_DEFAULT 164 #define ADC_INSTANCE ADC1 #define VBAT_ADC_PIN PA0 //#define CURRENT_METER_ADC_PIN PA5 //#define RSSI_ADC_PIN PB2 +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_VBAT #define SPEKTRUM_BIND #define BIND_PIN PB4 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 192971fd11..f58dcbe969 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -95,6 +95,7 @@ #define ADC_INSTANCE ADC2 #define VBAT_ADC_PIN PB2 +#define VBAT_SCALE_DEFAULT 77 #define LED_STRIP #define LED_STRIP_TIMER TIM1 From 9059254db6ae6d0b527066f1e0e274e61e3f0bd7 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 28 Jun 2016 22:00:23 +0100 Subject: [PATCH 031/108] Minor tidy of sensor code --- src/main/drivers/accgyro_mpu6050.c | 2 -- src/main/sensors/acceleration.h | 3 +-- src/main/sensors/barometer.h | 6 ++---- src/main/sensors/compass.h | 10 ++++------ src/main/sensors/gyro.c | 6 +++++- src/main/sensors/gyro.h | 3 ++- src/main/sensors/sensors.h | 2 +- 7 files changed, 15 insertions(+), 17 deletions(-) diff --git a/src/main/drivers/accgyro_mpu6050.c b/src/main/drivers/accgyro_mpu6050.c index d4fa0fb846..3cc3ac8f69 100644 --- a/src/main/drivers/accgyro_mpu6050.c +++ b/src/main/drivers/accgyro_mpu6050.c @@ -38,8 +38,6 @@ #include "accgyro_mpu.h" #include "accgyro_mpu6050.h" -extern uint8_t mpuLowPassFilter; - //#define DEBUG_MPU_DATA_READY_INTERRUPT // MPU6050, Standard address 0x68 diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index 9e56c2abea..dc98ae78ef 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -29,10 +29,9 @@ typedef enum { ACC_MPU6000 = 7, ACC_MPU6500 = 8, ACC_FAKE = 9, + ACC_MAX = ACC_FAKE } accelerationSensor_e; -#define ACC_MAX ACC_FAKE - extern sensor_align_e accAlign; extern acc_t acc; extern uint32_t accTargetLooptime; diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index 7ea2c1e5ba..0ef2638ad0 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -22,11 +22,11 @@ typedef enum { BARO_NONE = 1, BARO_BMP085 = 2, BARO_MS5611 = 3, - BARO_BMP280 = 4 + BARO_BMP280 = 4, + BARO_MAX = BARO_BMP280 } baroSensor_e; #define BARO_SAMPLE_COUNT_MAX 48 -#define BARO_MAX BARO_MS5611 typedef struct barometerConfig_s { uint8_t baro_sample_count; // size of baro filter array @@ -38,7 +38,6 @@ typedef struct barometerConfig_s { extern int32_t BaroAlt; extern int32_t baroTemperature; // Use temperature for telemetry -#ifdef BARO void useBarometerConfig(barometerConfig_t *barometerConfigToUse); bool isBaroCalibrationComplete(void); void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired); @@ -46,4 +45,3 @@ uint32_t baroUpdate(void); bool isBaroReady(void); int32_t baroCalculateAltitude(void); void performBaroCalibrationCycle(void); -#endif diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 0807ba4106..2f5ae7d21a 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -23,15 +23,13 @@ typedef enum { MAG_NONE = 1, MAG_HMC5883 = 2, MAG_AK8975 = 3, - MAG_AK8963 = 4 + MAG_AK8963 = 4, + MAG_MAX = MAG_AK8963 } magSensor_e; -#define MAG_MAX MAG_AK8963 - -#ifdef MAG void compassInit(void); -void updateCompass(flightDynamicsTrims_t *magZero); -#endif +union flightDynamicsTrims_u; +void updateCompass(union flightDynamicsTrims_u *magZero); extern int32_t magADC[XYZ_AXIS_COUNT]; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 48113e934a..c79d29013f 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -41,7 +41,7 @@ sensor_align_e gyroAlign = 0; int32_t gyroADC[XYZ_AXIS_COUNT]; float gyroADCf[XYZ_AXIS_COUNT]; -static int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 }; +static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 }; static const gyroConfig_t *gyroConfig; static biquad_t gyroFilterState[XYZ_AXIS_COUNT]; static uint8_t gyroSoftLpfHz; @@ -160,5 +160,9 @@ void gyroUpdate(void) gyroADCf[axis] = applyBiQuadFilter((float)gyroADC[axis], &gyroFilterState[axis]); gyroADC[axis] = lrintf(gyroADCf[axis]); } + } else { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + gyroADCf[axis] = gyroADC[axis]; + } } } diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 54069b8a64..2239eb6816 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -27,7 +27,8 @@ typedef enum { GYRO_MPU6000, GYRO_MPU6500, GYRO_MPU9250, - GYRO_FAKE + GYRO_FAKE, + GYRO_MAX = GYRO_FAKE } gyroSensor_e; extern gyro_t gyro; diff --git a/src/main/sensors/sensors.h b/src/main/sensors/sensors.h index 92e6907eef..f47b96d0b5 100644 --- a/src/main/sensors/sensors.h +++ b/src/main/sensors/sensors.h @@ -34,7 +34,7 @@ typedef struct int16_flightDynamicsTrims_s { int16_t yaw; } flightDynamicsTrims_def_t; -typedef union { +typedef union flightDynamicsTrims_u { int16_t raw[3]; flightDynamicsTrims_def_t values; } flightDynamicsTrims_t; From d3b51f2360dd23155b00d5d54d22502924506599 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 29 Jun 2016 18:06:08 +0100 Subject: [PATCH 032/108] Added count to sensor index enums --- src/main/sensors/initialisation.c | 2 +- src/main/sensors/sensors.h | 7 +++---- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 399ad7b842..0e75ad15f5 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -81,7 +81,7 @@ extern baro_t baro; extern acc_t acc; extern sensor_align_e gyroAlign; -uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; +uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; const extiConfig_t *selectMPUIntExtiConfig(void) diff --git a/src/main/sensors/sensors.h b/src/main/sensors/sensors.h index f47b96d0b5..9e6fdda92f 100644 --- a/src/main/sensors/sensors.h +++ b/src/main/sensors/sensors.h @@ -21,12 +21,11 @@ typedef enum { SENSOR_INDEX_GYRO = 0, SENSOR_INDEX_ACC, SENSOR_INDEX_BARO, - SENSOR_INDEX_MAG + SENSOR_INDEX_MAG, + SENSOR_INDEX_COUNT } sensorIndex_e; -#define MAX_SENSORS_TO_DETECT (SENSOR_INDEX_MAG + 1) - -extern uint8_t detectedSensors[MAX_SENSORS_TO_DETECT]; +extern uint8_t detectedSensors[SENSOR_INDEX_COUNT]; typedef struct int16_flightDynamicsTrims_s { int16_t roll; From c10129bc507a2cbc27af063e633ae2360b5557ad Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 29 Jun 2016 20:12:52 +0100 Subject: [PATCH 033/108] Combined timer output and inverted fields --- src/main/drivers/pwm_mapping.h | 2 -- src/main/drivers/pwm_output.c | 4 +-- src/main/drivers/timer.c | 2 +- src/main/drivers/timer.h | 7 +++-- src/main/target/ALIENFLIGHTF3/target.c | 28 +++++++++--------- src/main/target/ALIENFLIGHTF4/target.c | 26 ++++++++-------- src/main/target/BLUEJAYF4/target.c | 14 ++++----- src/main/target/CC3D/target.c | 24 +++++++-------- src/main/target/CHEBUZZF3/target.c | 36 +++++++++++------------ src/main/target/CJMCU/target.c | 28 +++++++++--------- src/main/target/COLIBRI_RACE/target.c | 22 +++++++------- src/main/target/DOGE/target.c | 18 ++++++------ src/main/target/EUSTM32F103RC/target.c | 28 +++++++++--------- src/main/target/FURYF3/target.c | 14 ++++----- src/main/target/FURYF4/target.c | 12 ++++---- src/main/target/IRCFUSIONF3/target.c | 34 ++++++++++----------- src/main/target/KISSFC/target.c | 24 +++++++-------- src/main/target/LUX_RACE/target.c | 22 +++++++------- src/main/target/MOTOLAB/target.c | 18 ++++++------ src/main/target/NAZE/target.c | 28 +++++++++--------- src/main/target/OLIMEXINO/target.c | 28 +++++++++--------- src/main/target/OMNIBUS/target.c | 24 +++++++-------- src/main/target/PIKOBLX/target.c | 18 ++++++------ src/main/target/PORT103R/target.c | 28 +++++++++--------- src/main/target/REVO/target.c | 24 +++++++-------- src/main/target/REVONANO/target.c | 24 +++++++-------- src/main/target/RMDO/target.c | 34 ++++++++++----------- src/main/target/SINGULARITY/target.c | 20 ++++++------- src/main/target/SIRINFPV/target.c | 12 ++++---- src/main/target/SPARKY/target.c | 22 +++++++------- src/main/target/SPRACINGF3/target.c | 34 ++++++++++----------- src/main/target/SPRACINGF3EVO/target.c | 24 +++++++-------- src/main/target/SPRACINGF3MINI/target.c | 26 ++++++++-------- src/main/target/STM32F3DISCOVERY/target.c | 28 +++++++++--------- src/main/target/X_RACERSPI/target.c | 34 ++++++++++----------- src/main/target/ZCOREF3/target.c | 34 ++++++++++----------- 36 files changed, 402 insertions(+), 403 deletions(-) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 5d577af8e0..40aa5d4d2a 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -93,8 +93,6 @@ typedef enum { PWM_PF_OUTPUT_PROTOCOL_ONESHOT = (1 << 4) } pwmPortFlags_e; -enum {PWM_INVERTED = 1}; - typedef struct pwmPortConfiguration_s { uint8_t index; pwmPortFlags_e flags; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index b445949381..277b47736d 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -97,9 +97,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 configTimeBase(timerHardware->tim, period, mhz); pwmGPIOConfig(timerHardware->tag, IOCFG_AF_PP); - pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->outputInverted); + pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); - if (timerHardware->outputEnable) { + if (timerHardware->output & TIMER_OUTPUT_ENABLED) { TIM_CtrlPWMOutputs(timerHardware->tim, ENABLE); } TIM_Cmd(timerHardware->tim, ENABLE); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 6999a9798e..37067ae254 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -456,7 +456,7 @@ void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHig if(outEnable) { TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; - if (timHw->outputInverted) { + if (timHw->output & TIMER_OUTPUT_INVERTED) { stateHigh = !stateHigh; } TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low; diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 0cd5f684ec..cdc461c690 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -76,13 +76,14 @@ typedef struct timerHardware_s { ioTag_t tag; uint8_t channel; uint8_t irq; - uint8_t outputEnable; + uint8_t output; ioConfig_t ioMode; #if defined(STM32F3) || defined(STM32F4) uint8_t alternateFunction; #endif - uint8_t outputInverted; } timerHardware_t; +enum {TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_INVERTED = 0x02}; + #ifdef STM32F1 #if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL) @@ -147,4 +148,4 @@ void timerForceOverflow(TIM_TypeDef *tim); void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration -rccPeriphTag_t timerRCC(TIM_TypeDef *tim); \ No newline at end of file +rccPeriphTag_t timerRCC(TIM_TypeDef *tim); diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 7b7e6c163d..ad85d7b9b9 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -52,33 +52,33 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // 6 x 3 pin headers // - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 - { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 // // 6 pin header // // PWM7-10 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N // // PPM PORT - Also USART2 RX (AF5) // - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 - //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 + //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 // USART3 RX/TX // RX conflicts with PPM port - //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 - //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 + //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 + //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 }; diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index 054b27e814..e6024280f5 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -73,19 +73,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM1 - PA8 RC1 - { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM2 - PB0 RC2 - { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM3 - PB1 RC3 - { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4 - { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1 + { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2 + { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3 + { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4 + { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM6 - PB8 OUT1 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM7 - PB9 OUT2 - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM8 - PA0 OUT3 - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM9 - PA1 OUT4 - { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM10 - PC6 OUT5 - { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM11 - PC7 OUT6 - { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC8 OUT7 - { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC9 OUT8 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3 + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8 }; diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index ff191e8225..24df5a7393 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -51,12 +51,12 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8, 0 }, // PPM IN - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0 }, // S1_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0 }, // S2_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0 }, // S3_OUT - { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0 }, // S4_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0 }, // S5_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0 }, // S6_OUT + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8 }, // PPM IN + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S1_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S2_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S3_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S4_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S6_OUT }; diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index abfe089aa9..c685f7e35a 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -128,17 +128,17 @@ const uint16_t airPWM_BP6[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // S1_IN - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S4_IN - Current - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S5_IN - Vbattery - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S6_IN - PPM IN - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S1_OUT - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S2_OUT - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S3_OUT - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, 0}, // S4_OUT - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, 0} // S6_OUT + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // S1_IN + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // S4_IN - Current + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // S5_IN - Vbattery + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // S6_IN - PPM IN + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP }, // S1_OUT + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP }, // S2_OUT + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP }, // S3_OUT + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP }, // S4_OUT + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP } // S6_OUT }; diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 68e163dbf7..132ff783f9 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -73,23 +73,23 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // INPUTS CH1-8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM2 - PB8 - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM3 - PB9 - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM4 - PC6 - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM5 - PC7 - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM6 - PC8 - { TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM7 - PF9 - { TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM8 - PF10 - { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PD12 - { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM10 - PD13 - { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM11 - PD14 - { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM12 - PD15 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM13 - PA1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM14 - PA2 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM15 - PA3 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM16 - PB0 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM17 - PB1 - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0} // PWM18 - PA4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM2 - PB8 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM3 - PB9 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM4 - PC6 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM5 - PC7 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM6 - PC8 + { TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM7 - PF9 + { TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM8 - PF10 + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PD12 + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM10 - PD13 + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM11 - PD14 + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM12 - PD15 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM13 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM14 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM15 - PA3 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM16 - PB0 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM17 - PB1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 } // PWM18 - PA4 }; diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index b84a104543..926f3efa03 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -38,19 +38,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6 }; diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c index 323a1e74de..675067e068 100644 --- a/src/main/target/COLIBRI_RACE/target.c +++ b/src/main/target/COLIBRI_RACE/target.c @@ -67,16 +67,16 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PC6 - { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PC7 - { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PMW4 - PC8 - { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PC9 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA2 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PA3 - { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM10 - PB14 - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM11 - PB15 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15 }; diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index 958339b1c3..ebd5e6f1f0 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -58,17 +58,17 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB9 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9 - { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PMW4 - PA10 - { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM5 - PA9 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 + { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10 + { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM8 - PB1 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM9 - PB0 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM8 - PB1 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM9 - PB0 }; diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c index 2527bc389d..6e1b4ae6b6 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, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0 } // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6 }; diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 656c75e6dc..4dc593bb3f 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -52,15 +52,15 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PPM IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PPM IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - S1 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - S2 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - S1 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2 { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM6 - S3 - { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - S4 + { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO TIMER - LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP }; diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c index b6dbf5fe7f..c5bb0486c0 100644 --- a/src/main/target/FURYF4/target.c +++ b/src/main/target/FURYF4/target.c @@ -42,13 +42,13 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PPM_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM_IN - { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0}, // S1_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S2_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S3_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S4_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S1_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT -// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5, 0}, // LED Strip +// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip }; diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 7728a6f4f2..7207468fae 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -81,22 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index db129454a4..60f2a07363 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -48,18 +48,18 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, PWM_INVERTED}, - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, PWM_INVERTED}, - { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_6}, + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_2}, + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, - { TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_10,0}, - { TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5, 0}, + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, + { TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_10}, + { TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5}, }; diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index b665072acf..e26bb29500 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -66,16 +66,16 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PC6 - { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PC7 - { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PMW4 - PC8 - { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PC9 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA2 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PA3 - { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM10 - PB14 - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM11 - PB15 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15 }; diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index 47789fd4f8..b624db7ccf 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -42,14 +42,14 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index 9e35b3a177..110ce3140a 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6 }; diff --git a/src/main/target/OLIMEXINO/target.c b/src/main/target/OLIMEXINO/target.c index 35bf464de1..1b75af4224 100644 --- a/src/main/target/OLIMEXINO/target.c +++ b/src/main/target/OLIMEXINO/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6 }; diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index 1784dcf51b..94250435ab 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -66,24 +66,24 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM Pad - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB4 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent // Used by SPI1, MAX7456 - //{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - //{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 + //{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 + //{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM5 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM6 - PA3 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA1 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM5 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM6 - PA3 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) // LED Strip Pad - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c index 47789fd4f8..b624db7ccf 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/PIKOBLX/target.c @@ -42,14 +42,14 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/PORT103R/target.c b/src/main/target/PORT103R/target.c index 7e71ab1d61..42ce07beca 100644 --- a/src/main/target/PORT103R/target.c +++ b/src/main/target/PORT103R/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6 }; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index be834daf36..b32c5175f0 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -71,19 +71,19 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12, 0}, // PPM (5th pin on FlexiIO port) - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12, 0}, // S2_IN - GPIO_PartialRemap_TIM3 - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S3_IN - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S4_IN - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S5_IN - { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S6_IN + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port) + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S3_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S1_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S2_OUT - { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9, 0}, // S3_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S4_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S6_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2 }, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S6_OUT }; diff --git a/src/main/target/REVONANO/target.c b/src/main/target/REVONANO/target.c index 8e5db9defc..53d4042172 100644 --- a/src/main/target/REVONANO/target.c +++ b/src/main/target/REVONANO/target.c @@ -86,18 +86,18 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // PPM - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S2_IN - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S3_IN - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S4_IN - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S5_IN - { TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S6_IN - { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // S1_OUT - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S2_OUT - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // S3_OUT - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // S5_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // S6_OUT + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // PPM + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_IN + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S4_IN + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_IN + { TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN + { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_OUT + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S2_OUT + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S3_OUT + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S4_OUT + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT }; diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 7728a6f4f2..eaeb18fca4 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -81,22 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c index fe6106ec9e..645bd323f5 100644 --- a/src/main/target/SINGULARITY/target.c +++ b/src/main/target/SINGULARITY/target.c @@ -60,15 +60,15 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PPM/SERIAL RX - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // SOFTSERIAL1 RX (NC) - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // SOFTSERIAL1 TX - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // LED_STRIP + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PPM/SERIAL RX + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 RX (NC) + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 TX + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // LED_STRIP }; diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c index 4ac409d394..dfe1517fb4 100644 --- a/src/main/target/SIRINFPV/target.c +++ b/src/main/target/SIRINFPV/target.c @@ -49,13 +49,13 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PB6 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB6 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PB6 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB6 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4 }; diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index 41fe8f2b8f..d5ecdcc96f 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -48,18 +48,18 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // 6 3-pin headers - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 - { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 // PWM7 - PMW10 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N // PPM PORT - Also USART2 RX (AF5) - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 }; diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index ddebee117f..122f07bb0a 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -82,25 +82,25 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, 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, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index a4b8890d91..1ac9743d3e 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -67,17 +67,17 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM / UART2 RX - { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PPM - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM3 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM8 - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8 + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 6a02620201..bc0d06cee6 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -68,27 +68,27 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM Pad #ifdef SPRACINGF3MINI_MKII_REVA - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB5 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB5 // PB4 / TIM3 CH1 is connected to USBPresent #else - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB4 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent #endif - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM5 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM6 - PA3 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA1 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM5 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM6 - PA3 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) // LED Strip Pad - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 1d2e615ead..dcf2426cee 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -73,19 +73,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM2 - PB8 - { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM3 - PB9 - { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM4 - PC6 - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM5 - PC7 - { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM6 - PC8 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM7 - PB1 - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM8 - PA2 - { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PD12 - { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM10 - PD13 - { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM11 - PD14 - { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM12 - PD15 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM13 - PA1 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0} // PWM14 - PA2 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM2 - PB8 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM3 - PB9 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM4 - PC6 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM5 - PC7 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM6 - PC8 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM7 - PB1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM8 - PA2 + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PD12 + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM10 - PD13 + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM11 - PD14 + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM12 - PD15 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM13 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 } // PWM14 - PA2 }; diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index 9c0bd04034..f2ad959f8d 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -82,24 +82,24 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c index e3b40ee630..a3cfdc7339 100644 --- a/src/main/target/ZCOREF3/target.c +++ b/src/main/target/ZCOREF3/target.c @@ -81,24 +81,24 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; From ceb9ef2db277098d721df482e6937ea7e589e413 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 30 Jun 2016 08:32:40 +0100 Subject: [PATCH 034/108] Added facility to set rx serial provider in for target. --- src/main/config/config.c | 30 +++++++++++++++----------- src/main/target/ALIENFLIGHTF3/target.h | 5 +++-- src/main/target/ALIENFLIGHTF4/target.h | 5 +++-- src/main/target/FURYF3/target.h | 4 ++-- src/main/target/FURYF4/target.h | 7 +++--- src/main/target/KISSFC/target.h | 5 +++-- src/main/target/NAZE/target.h | 16 ++++++++------ src/main/target/SPRACINGF3/target.h | 4 ++-- 8 files changed, 42 insertions(+), 34 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 284c59097b..5bcd1e923b 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -268,8 +268,13 @@ void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig) void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig) { +#ifdef BRUSHED_MOTORS + escAndServoConfig->minthrottle = 1000; + escAndServoConfig->maxthrottle = 2000; +#else escAndServoConfig->minthrottle = 1150; escAndServoConfig->maxthrottle = 1850; +#endif escAndServoConfig->mincommand = 1000; escAndServoConfig->servoCenterPulse = 1500; escAndServoConfig->escDesyncProtection = 0; @@ -415,8 +420,6 @@ uint16_t getCurrentMinthrottle(void) // Default settings static void resetConf(void) { - int i; - // Clear all configuration memset(&masterConfig, 0, sizeof(master_t)); setProfile(0); @@ -477,7 +480,11 @@ static void resetConf(void) resetTelemetryConfig(&masterConfig.telemetryConfig); +#ifdef SERIALRX_PROVIDER + masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER; +#else masterConfig.rxConfig.serialrx_provider = 0; +#endif masterConfig.rxConfig.sbus_inversion = 1; masterConfig.rxConfig.spektrum_sat_bind = 0; masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; @@ -487,7 +494,7 @@ static void resetConf(void) masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection - for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { + for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i]; channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc); @@ -549,8 +556,7 @@ static void resetConf(void) resetPidProfile(¤tProfile->pidProfile); - uint8_t rI; - for (rI = 0; rI Date: Fri, 1 Jul 2016 01:30:04 -0700 Subject: [PATCH 035/108] 0x00 is reserved for string null byte termination, move the voltage symbol to 0x06 --- src/main/drivers/max7456_symbols.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/max7456_symbols.h b/src/main/drivers/max7456_symbols.h index 2030cb956b..b2e8da72b5 100644 --- a/src/main/drivers/max7456_symbols.h +++ b/src/main/drivers/max7456_symbols.h @@ -176,7 +176,7 @@ #define SYM_FT 0x0F // Voltage and amperage -#define SYM_VOLT 0x00 +#define SYM_VOLT 0x06 #define SYM_AMP 0x9A #define SYM_MAH 0xA4 #define SYM_WATT 0x57 From 2d070a35076b5c116d8505d3974dfc84cffbd4b3 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Fri, 1 Jul 2016 01:53:45 -0700 Subject: [PATCH 036/108] Re-design DMA driver --- src/main/drivers/dma.c | 93 ++++----- src/main/drivers/dma.h | 91 +++++++-- src/main/drivers/dma_stm32f4xx.c | 75 ++++--- src/main/drivers/light_ws2811strip.c | 11 +- .../drivers/light_ws2811strip_stm32f10x.c | 17 +- .../drivers/light_ws2811strip_stm32f30x.c | 17 +- .../drivers/light_ws2811strip_stm32f4xx.c | 31 ++- src/main/drivers/max7456.c | 20 +- src/main/drivers/max7456_symbols.h | 2 +- src/main/drivers/serial_uart_stm32f10x.c | 39 ++-- src/main/drivers/serial_uart_stm32f30x.c | 84 +++----- src/main/drivers/serial_uart_stm32f4xx.c | 185 +++--------------- src/main/drivers/transponder_ir.c | 10 +- src/main/drivers/transponder_ir_stm32f30x.c | 9 +- src/main/target/OMNIBUS/target.h | 4 +- src/main/target/SIRINFPV/target.h | 5 +- 16 files changed, 299 insertions(+), 394 deletions(-) diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index cd17553e08..cbcaa5eafb 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -23,61 +23,66 @@ #include "build_config.h" +#include "drivers/nvic.h" #include "drivers/dma.h" /* - * DMA handlers for DMA resources that are shared between different features depending on run-time configuration. + * DMA descriptors. */ -static dmaHandlers_t dmaHandlers; +static dmaChannelDescriptor_t dmaDescriptors[] = { + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel1, 0, DMA1_Channel1_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel2, 4, DMA1_Channel2_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel3, 8, DMA1_Channel3_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel4, 12, DMA1_Channel4_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel5, 16, DMA1_Channel5_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel6, 20, DMA1_Channel6_IRQn, RCC_AHBPeriph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Channel7, 24, DMA1_Channel7_IRQn, RCC_AHBPeriph_DMA1), +#if defined(STM32F3) || defined(STM32F10X_CL) + DEFINE_DMA_CHANNEL(DMA2, DMA2_Channel1, 0, DMA2_Channel1_IRQn, RCC_AHBPeriph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Channel2, 4, DMA2_Channel2_IRQn, RCC_AHBPeriph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Channel3, 8, DMA2_Channel3_IRQn, RCC_AHBPeriph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Channel4, 12, DMA2_Channel4_IRQn, RCC_AHBPeriph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Channel5, 16, DMA2_Channel5_IRQn, RCC_AHBPeriph_DMA2), +#endif +}; -void dmaNoOpHandler(DMA_Channel_TypeDef *channel) -{ - UNUSED(channel); -} +/* + * DMA IRQ Handlers + */ +DEFINE_DMA_IRQ_HANDLER(1, 1, DMA1_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 2, DMA1_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 3, DMA1_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 4, DMA1_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_CH5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_CH6_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_CH7_HANDLER) -void DMA1_Channel2_IRQHandler(void) -{ - dmaHandlers.dma1Channel2IRQHandler(DMA1_Channel2); -} +#if defined(STM32F3) || defined(STM32F10X_CL) +DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER) +#endif -void DMA1_Channel3_IRQHandler(void) -{ - dmaHandlers.dma1Channel3IRQHandler(DMA1_Channel3); -} - -void DMA1_Channel6_IRQHandler(void) -{ - dmaHandlers.dma1Channel6IRQHandler(DMA1_Channel6); -} - -void DMA1_Channel7_IRQHandler(void) -{ - dmaHandlers.dma1Channel7IRQHandler(DMA1_Channel7); -} void dmaInit(void) { - memset(&dmaHandlers, 0, sizeof(dmaHandlers)); - dmaHandlers.dma1Channel2IRQHandler = dmaNoOpHandler; - dmaHandlers.dma1Channel3IRQHandler = dmaNoOpHandler; - dmaHandlers.dma1Channel6IRQHandler = dmaNoOpHandler; - dmaHandlers.dma1Channel7IRQHandler = dmaNoOpHandler; + // TODO: Do we need this? } -void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback) +void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam) { - switch (identifier) { - case DMA1_CH2_HANDLER: - dmaHandlers.dma1Channel2IRQHandler = callback; - break; - case DMA1_CH3_HANDLER: - dmaHandlers.dma1Channel3IRQHandler = callback; - break; - case DMA1_CH6_HANDLER: - dmaHandlers.dma1Channel6IRQHandler = callback; - break; - case DMA1_CH7_HANDLER: - dmaHandlers.dma1Channel7IRQHandler = callback; - break; - } + NVIC_InitTypeDef NVIC_InitStructure; + + RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rrc, ENABLE); + dmaDescriptors[identifier].irqHandlerCallback = callback; + dmaDescriptors[identifier].userParam = userParam; + + NVIC_InitStructure.NVIC_IRQChannel = dmaDescriptors[identifier].irqN; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(priority); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(priority); + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); } + diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 9cb34c7665..345c7b2ed8 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -15,37 +15,98 @@ * along with Cleanflight. If not, see . */ + +struct dmaChannelDescriptor_s; +typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor); + #ifdef STM32F4 typedef void(*dmaCallbackHandlerFuncPtr)(DMA_Stream_TypeDef *stream); typedef enum { - DMA1_ST2_HANDLER = 0, + DMA1_ST1_HANDLER = 0, + DMA1_ST2_HANDLER, + DMA1_ST3_HANDLER, + DMA1_ST4_HANDLER, + DMA1_ST5_HANDLER, + DMA1_ST6_HANDLER, DMA1_ST7_HANDLER, + DMA2_ST1_HANDLER, + DMA2_ST2_HANDLER, + DMA2_ST3_HANDLER, + DMA2_ST4_HANDLER, + DMA2_ST5_HANDLER, + DMA2_ST6_HANDLER, + DMA2_ST7_HANDLER, } dmaHandlerIdentifier_e; -typedef struct dmaHandlers_s { - dmaCallbackHandlerFuncPtr dma1Stream2IRQHandler; - dmaCallbackHandlerFuncPtr dma1Stream7IRQHandler; -} dmaHandlers_t; +typedef struct dmaChannelDescriptor_s { + DMA_TypeDef* dma; + DMA_Stream_TypeDef* stream; + dmaCallbackHandlerFuncPtr irqHandlerCallback; + uint8_t flagsShift; + IRQn_Type irqN; + uint32_t rrc; + uint32_t userParam; +} dmaChannelDescriptor_t; + +#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rrc = r, .userParam = 0} +#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\ + if (dmaDescriptors[i].irqHandlerCallback)\ + dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ + } + +#define DMA_CLEAR_FLAG(d, flag) d->flagsShift > 31 ? d->dma->HIFCR = (flag << (d->flagsShift - 32)) : d->dma->LIFCR = (flag << d->flagsShift) +#define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift)) + + +#define DMA_IT_TCIF ((uint32_t)0x00000020) +#define DMA_IT_HTIF ((uint32_t)0x00000010) +#define DMA_IT_TEIF ((uint32_t)0x00000008) +#define DMA_IT_DMEIF ((uint32_t)0x00000004) +#define DMA_IT_FEIF ((uint32_t)0x00000001) #else -typedef void (*dmaCallbackHandlerFuncPtr)(DMA_Channel_TypeDef *channel); - typedef enum { - DMA1_CH2_HANDLER = 0, + DMA1_CH1_HANDLER = 0, + DMA1_CH2_HANDLER, DMA1_CH3_HANDLER, + DMA1_CH4_HANDLER, + DMA1_CH5_HANDLER, DMA1_CH6_HANDLER, DMA1_CH7_HANDLER, + DMA2_CH1_HANDLER, + DMA2_CH2_HANDLER, + DMA2_CH3_HANDLER, + DMA2_CH4_HANDLER, + DMA2_CH5_HANDLER, } dmaHandlerIdentifier_e; -typedef struct dmaHandlers_s { - dmaCallbackHandlerFuncPtr dma1Channel2IRQHandler; - dmaCallbackHandlerFuncPtr dma1Channel3IRQHandler; - dmaCallbackHandlerFuncPtr dma1Channel6IRQHandler; - dmaCallbackHandlerFuncPtr dma1Channel7IRQHandler; -} dmaHandlers_t; +typedef struct dmaChannelDescriptor_s { + DMA_TypeDef* dma; + DMA_Channel_TypeDef* channel; + dmaCallbackHandlerFuncPtr irqHandlerCallback; + uint8_t flagsShift; + IRQn_Type irqN; + uint32_t rrc; + uint32_t userParam; +} dmaChannelDescriptor_t; + +#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rrc = r, .userParam = 0} +#define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\ + if (dmaDescriptors[i].irqHandlerCallback)\ + dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ + } + +#define DMA_CLEAR_FLAG(d, flag) d->dma->IFCR = (flag << d->flagsShift) +#define DMA_GET_FLAG_STATUS(d, flag) (d->dma->ISR & (flag << d->flagsShift)) + +#define DMA_IT_TCIF ((uint32_t)0x00000002) +#define DMA_IT_HTIF ((uint32_t)0x00000004) +#define DMA_IT_TEIF ((uint32_t)0x00000008) + #endif void dmaInit(void); -void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback); +void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam); + diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index fefbae2801..3f57dfd985 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -23,43 +23,66 @@ #include "build_config.h" +#include "drivers/nvic.h" #include "drivers/dma.h" /* - * DMA handlers for DMA resources that are shared between different features depending on run-time configuration. + * DMA descriptors. */ -static dmaHandlers_t dmaHandlers; +static dmaChannelDescriptor_t dmaDescriptors[] = { + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream0, 0, DMA1_Stream0_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream1, 6, DMA1_Stream1_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream2, 16, DMA1_Stream2_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream3, 22, DMA1_Stream3_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream4, 32, DMA1_Stream4_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream5, 38, DMA1_Stream5_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream6, 48, DMA1_Stream6_IRQn, RCC_AHB1Periph_DMA1), + DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream7, 54, DMA1_Stream7_IRQn, RCC_AHB1Periph_DMA1), -void dmaNoOpHandler(DMA_Stream_TypeDef *stream) -{ - UNUSED(stream); -} + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream0, 0, DMA2_Stream0_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream1, 6, DMA2_Stream1_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream2, 16, DMA2_Stream2_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream3, 22, DMA2_Stream3_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream4, 32, DMA2_Stream4_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream5, 38, DMA2_Stream5_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream6, 48, DMA2_Stream6_IRQn, RCC_AHB1Periph_DMA2), + DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream7, 54, DMA2_Stream7_IRQn, RCC_AHB1Periph_DMA2), -void DMA1_Stream2_IRQHandler(void) -{ - dmaHandlers.dma1Stream2IRQHandler(DMA1_Stream2); -} +}; + +/* + * DMA IRQ Handlers + */ +DEFINE_DMA_IRQ_HANDLER(1, 1, DMA1_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 2, DMA1_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 3, DMA1_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 4, DMA1_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_CH5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_CH6_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_CH7_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_CH1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_CH2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_CH3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER) -void DMA1_Stream7_IRQHandler(void) -{ - dmaHandlers.dma1Stream7IRQHandler(DMA1_Stream7); -} void dmaInit(void) { - memset(&dmaHandlers, 0, sizeof(dmaHandlers)); - dmaHandlers.dma1Stream2IRQHandler = dmaNoOpHandler; - dmaHandlers.dma1Stream7IRQHandler = dmaNoOpHandler; + // TODO: Do we need this? } -void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback) +void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority) { - switch (identifier) { - case DMA1_ST2_HANDLER: - dmaHandlers.dma1Stream2IRQHandler = callback; - break; - case DMA1_ST7_HANDLER: - dmaHandlers.dma1Stream7IRQHandler = callback; - break; - } + NVIC_InitTypeDef NVIC_InitStructure; + + RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].periphClk, ENABLE); + dmaDescriptors[identifier].irqHandlerCallback = callback; + + NVIC_InitStructure.NVIC_IRQChannel = dmaDescriptors[identifier].irqN; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(priority); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(priority); + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); } + diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index 3821350f57..75dac72d43 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -80,18 +80,9 @@ void setStripColors(const hsvColor_t *colors) } } -void ws2811DMAHandler(DMA_Channel_TypeDef *channel) { - if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) { - ws2811LedDataTransferInProgress = 0; - DMA_Cmd(channel, DISABLE); - DMA_ClearFlag(WS2811_DMA_TC_FLAG); - } -} - void ws2811LedStripInit(void) { memset(&ledStripDMABuffer, 0, WS2811_DMA_BUFFER_SIZE); - dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); ws2811LedStripHardwareInit(); ws2811UpdateStrip(); } @@ -173,4 +164,4 @@ void ws2811UpdateStrip(void) ws2811LedStripDMAEnable(); } -#endif \ No newline at end of file +#endif diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index b7f1bd4138..f780901f1c 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -23,6 +23,15 @@ #include "common/color.h" #include "drivers/light_ws2811strip.h" #include "nvic.h" +#include "dma.h" + +static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) { + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(descriptor->channel, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} void ws2811LedStripHardwareInit(void) { @@ -100,13 +109,7 @@ void ws2811LedStripHardwareInit(void) DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE); - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(DMA1_CH6_HANDLER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); setStripColor(&hsv_white); ws2811UpdateStrip(); diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index fbcc8d3fb0..9deaff9e4b 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -22,6 +22,7 @@ #include "gpio.h" #include "nvic.h" +#include "dma.h" #include "common/color.h" #include "drivers/light_ws2811strip.h" @@ -41,6 +42,14 @@ #endif +static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) { + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(descriptor->channel, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} + void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; @@ -114,13 +123,7 @@ void ws2811LedStripHardwareInit(void) DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE); - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = WS2811_IRQ; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); setStripColor(&hsv_white); ws2811UpdateStrip(); diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index d85f1c5757..65e1d51819 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -23,8 +23,20 @@ #include "common/color.h" #include "light_ws2811strip.h" #include "nvic.h" +#include "dma.h" #ifdef LED_STRIP + +static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) +{ + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(descriptor->stream, DISABLE); + TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} + void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; @@ -98,28 +110,11 @@ void ws2811LedStripHardwareInit(void) DMA_ITConfig(DMA1_Stream2, DMA_IT_TC, ENABLE); DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); // clear DMA1 Channel 6 transfer complete flag - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Stream2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - + dmaSetHandler(DMA1_ST2_HANDLER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); setStripColor(&hsv_white); ws2811UpdateStrip(); } -void DMA1_Stream2_IRQHandler(void) -{ - if (DMA_GetFlagStatus(DMA1_Stream2, DMA_FLAG_TCIF2)) { - ws2811LedDataTransferInProgress = 0; - DMA_Cmd(DMA1_Stream2, DISABLE); - TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE); - DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); - } -} - void ws2811LedStripDMAEnable(void) { DMA_SetCurrDataCounter(DMA1_Stream2, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 239c294125..eeefa940d9 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -30,6 +30,7 @@ #include "drivers/light_led.h" #include "drivers/system.h" #include "drivers/nvic.h" +#include "drivers/dma.h" #include "max7456.h" #include "max7456_symbols.h" @@ -119,8 +120,8 @@ static void max7456_send_dma(void* tx_buffer, void* rx_buffer, uint16_t buffer_s SPI_I2S_DMAReq_Tx, ENABLE); } -void MAX7456_DMA_IRQ_HANDLER_FUNCTION (void) { - if (DMA_GetFlagStatus(MAX7456_DMA_TC_FLAG)) { +void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor) { + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { #ifdef MAX7456_DMA_CHANNEL_RX DMA_Cmd(MAX7456_DMA_CHANNEL_RX, DISABLE); #else @@ -131,7 +132,7 @@ void MAX7456_DMA_IRQ_HANDLER_FUNCTION (void) { #endif DMA_Cmd(MAX7456_DMA_CHANNEL_TX, DISABLE); - DMA_ClearFlag(MAX7456_DMA_TC_FLAG); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); SPI_I2S_DMACmd(MAX7456_SPI_INSTANCE, #ifdef MAX7456_DMA_CHANNEL_RX @@ -141,7 +142,7 @@ void MAX7456_DMA_IRQ_HANDLER_FUNCTION (void) { DISABLE_MAX7456; for (uint16_t x = 0; x < max_screen_size; x++) - max7456_screen[x + 3] = MAX7456ADD_DMDI; + max7456_screen[x + 3] = MAX7456_CHAR(' '); dma_transaction_in_progress = 0; } } @@ -206,7 +207,7 @@ void max7456_init(uint8_t video_system) delay(100); for (x = 0; x < max_screen_size; x++) - SCREEN_BUFFER[x] = MAX7456_CHAR(0); + SCREEN_BUFFER[x] = MAX7456_CHAR(' '); #ifdef MAX7456_DMA_CHANNEL_TX max7456_screen[0] = (uint16_t)(MAX7456ADD_DMAH | (0 << 8)); @@ -215,14 +216,7 @@ void max7456_init(uint8_t video_system) max7456_screen[max_screen_size + 3] = (uint16_t)(MAX7456ADD_DMDI | (0xFF << 8)); max7456_screen[max_screen_size + 4] = (uint16_t)(MAX7456ADD_DMM | (0 << 8)); - RCC_AHBPeriphClockCmd(MAX7456_DMA_PERIPH_CLOCK, ENABLE); - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = MAX7456_DMA_IRQ_HANDLER_ID; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAX7456_DMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAX7456_DMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(MAX7456_DMA_IRQ_HANDLER_ID, max7456_dma_irq_handler, NVIC_PRIO_MAX7456_DMA, 0); #endif } diff --git a/src/main/drivers/max7456_symbols.h b/src/main/drivers/max7456_symbols.h index 2030cb956b..b2e8da72b5 100644 --- a/src/main/drivers/max7456_symbols.h +++ b/src/main/drivers/max7456_symbols.h @@ -176,7 +176,7 @@ #define SYM_FT 0x0F // Voltage and amperage -#define SYM_VOLT 0x00 +#define SYM_VOLT 0x06 #define SYM_AMP 0x9A #define SYM_MAH 0xA4 #define SYM_WATT 0x57 diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 08c16fa2f3..999df9bd5b 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -31,6 +31,7 @@ #include "system.h" #include "gpio.h" #include "nvic.h" +#include "dma.h" #include "serial.h" #include "serial_uart.h" @@ -83,6 +84,22 @@ void usartIrqCallback(uartPort_t *s) } #ifdef USE_USART1 + +// USART1 Tx DMA Handler +void USART1_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +{ + uartPort_t *s = &uartPort1; + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + DMA_Cmd(descriptor->channel, DISABLE); + + if (s->port.txBufferHead != s->port.txBufferTail) + uartStartTxDMA(s); + else + s->txDMAEmpty = true; +} + + + // USART1 - Telemetry (RX/TX by DMA) uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { @@ -90,7 +107,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; gpio_config_t gpio; - NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort1; s->port.vTable = uartVTable; @@ -137,14 +153,12 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio } // DMA TX Interrupt - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(DMA1_CH4_HANDLER, USART1_DMA_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, 0); #ifndef USE_USART1_RX_DMA // RX/TX Interrupt + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1); @@ -156,19 +170,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio } -// USART1 Tx DMA Handler -void DMA1_Channel4_IRQHandler(void) -{ - uartPort_t *s = &uartPort1; - DMA_ClearITPendingBit(DMA1_IT_TC4); - DMA_Cmd(s->txDMAChannel, DISABLE); - - if (s->port.txBufferHead != s->port.txBufferTail) - uartStartTxDMA(s); - else - s->txDMAEmpty = true; -} - // USART1 Rx/Tx IRQ Handler void USART1_IRQHandler(void) { diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index c124f05e20..78cfd482a9 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -32,6 +32,7 @@ #include "system.h" #include "gpio.h" #include "nvic.h" +#include "dma.h" #include "serial.h" #include "serial_uart.h" @@ -81,13 +82,24 @@ static uartPort_t uartPort2; static uartPort_t uartPort3; #endif +static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) +{ + uartPort_t *s = (uartPort_t*)(descriptor->userParam); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + DMA_Cmd(descriptor->channel, DISABLE); + + if (s->port.txBufferHead != s->port.txBufferTail) + uartStartTxDMA(s); + else + s->txDMAEmpty = true; +} + #ifdef USE_USART1 uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; - NVIC_InitTypeDef NVIC_InitStructure; GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort1; @@ -139,14 +151,12 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio } } - // DMA TX Interrupt - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, 0); + #ifndef USE_USART1_RX_DMA + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_RXDMA); @@ -164,7 +174,6 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; - NVIC_InitTypeDef NVIC_InitStructure; GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort2; @@ -222,14 +231,12 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio #ifdef USE_USART2_TX_DMA // DMA TX Interrupt - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel7_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, 0); #endif #ifndef USE_USART2_RX_DMA + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_RXDMA); @@ -247,7 +254,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE]; - NVIC_InitTypeDef NVIC_InitStructure; GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort3; @@ -305,14 +311,12 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio #ifdef USE_USART3_TX_DMA // DMA TX Interrupt - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_TXDMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, 0); #endif #ifndef USE_USART3_RX_DMA + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_RXDMA); @@ -324,48 +328,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -static void handleUsartTxDma(uartPort_t *s) -{ - DMA_Cmd(s->txDMAChannel, DISABLE); - - if (s->port.txBufferHead != s->port.txBufferTail) - uartStartTxDMA(s); - else - s->txDMAEmpty = true; -} - -// USART1 Tx DMA Handler -void DMA1_Channel4_IRQHandler(void) -{ - uartPort_t *s = &uartPort1; - DMA_ClearITPendingBit(DMA1_IT_TC4); - DMA_Cmd(DMA1_Channel4, DISABLE); - handleUsartTxDma(s); -} - -#ifdef USE_USART2_TX_DMA -// USART2 Tx DMA Handler -void DMA1_Channel7_IRQHandler(void) -{ - uartPort_t *s = &uartPort2; - DMA_ClearITPendingBit(DMA1_IT_TC7); - DMA_Cmd(DMA1_Channel7, DISABLE); - handleUsartTxDma(s); -} -#endif - -// USART3 Tx DMA Handler -#ifdef USE_USART3_TX_DMA -void DMA1_Channel2_IRQHandler(void) -{ - uartPort_t *s = &uartPort3; - DMA_ClearITPendingBit(DMA1_IT_TC2); - DMA_Cmd(DMA1_Channel2, DISABLE); - handleUsartTxDma(s); -} -#endif - - void usartIrqHandler(uartPort_t *s) { uint32_t ISR = s->USARTx->ISR; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index f5bba84699..d8c8ee5df5 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -87,7 +87,7 @@ static uartDevice_t uart1 = .rcc_ahb1 = USART1_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART1), - .txIrq = DMA2_Stream7_IRQn, + .txIrq = DMA2_ST7_HANDLER, .rxIrq = USART1_IRQn, .txPriority = NVIC_PRIO_SERIALUART1_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART1 @@ -110,7 +110,7 @@ static uartDevice_t uart2 = .rcc_ahb1 = USART2_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART2), - .txIrq = DMA1_Stream6_IRQn, + .txIrq = DMA1_ST6_HANDLER, .rxIrq = USART2_IRQn, .txPriority = NVIC_PRIO_SERIALUART2_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART2 @@ -133,7 +133,7 @@ static uartDevice_t uart3 = .rcc_ahb1 = USART3_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART3), - .txIrq = DMA1_Stream3_IRQn, + .txIrq = DMA1_ST3_HANDLER, .rxIrq = USART3_IRQn, .txPriority = NVIC_PRIO_SERIALUART3_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART3 @@ -156,7 +156,7 @@ static uartDevice_t uart4 = .rcc_ahb1 = USART4_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART4), - .txIrq = DMA1_Stream4_IRQn, + .txIrq = DMA1_ST4_HANDLER, .rxIrq = UART4_IRQn, .txPriority = NVIC_PRIO_SERIALUART4_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART4 @@ -179,7 +179,7 @@ static uartDevice_t uart5 = .rcc_ahb1 = USART5_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART5), - .txIrq = DMA2_Stream7_IRQn, + .txIrq = DMA2_ST7_HANDLER, .rxIrq = UART5_IRQn, .txPriority = NVIC_PRIO_SERIALUART5_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART5 @@ -202,7 +202,7 @@ static uartDevice_t uart6 = .rcc_ahb1 = USART6_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART6), - .txIrq = DMA2_Stream6_IRQn, + .txIrq = DMA2_ST6_HANDLER, .rxIrq = USART6_IRQn, .txPriority = NVIC_PRIO_SERIALUART6_TXDMA, .rxPriority = NVIC_PRIO_SERIALUART6 @@ -278,6 +278,29 @@ static void handleUsartTxDma(uartPort_t *s) s->txDMAEmpty = true; } +void dmaIRQHandler(dmaChannelDescriptor_t descriptor) +{ + uartPort_t *s = &((uartDevice_t*)(descriptor->userParam)->port); + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF); + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF); + } + handleUsartTxDma(s); + } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF); + } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF)) + { + DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF); + } +} + uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; @@ -336,11 +359,7 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p } // DMA TX Interrupt - NVIC_InitStructure.NVIC_IRQChannel = uart->txIrq; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(uart->txPriority); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(uart->txPriority); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + dmaSetHandler(uart->txIrq, dmaIRQHandler, uart->txPriority, (uint32_t)uart); if (!(s->rxDMAChannel)) { NVIC_InitStructure.NVIC_IRQChannel = uart->rxIrq; @@ -359,30 +378,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_1, baudRate, mode, options); } -// USART1 Tx DMA Handler -void DMA2_Stream7_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); - } -} - // USART1 Rx/Tx IRQ Handler void USART1_IRQHandler(void) { @@ -398,30 +393,6 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_2, baudRate, mode, options); } -// USART2 Tx DMA Handler -void DMA1_Stream6_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); - } -} - void USART2_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); @@ -436,30 +407,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_3, baudRate, mode, options); } -// USART3 Tx DMA Handler -void DMA1_Stream3_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF3)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3); - } -} - void USART3_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); @@ -474,30 +421,6 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_4, baudRate, mode, options); } -// USART4 Tx DMA Handler -void DMA1_Stream4_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF4)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4); - } -} - void UART4_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); @@ -512,30 +435,6 @@ uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_5, baudRate, mode, options); } -// USART5 Tx DMA Handler -void DMA1_Stream7_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7); - } -} - void UART5_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); @@ -550,30 +449,6 @@ uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t optio return serialUSART(UARTDEV_6, baudRate, mode, options); } -// USART6 Tx DMA Handler -void DMA2_Stream6_IRQHandler(void) -{ - uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); - if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6)) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6); - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6); - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6); - } - handleUsartTxDma(s); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6); - } - if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET) - { - DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6); - } -} - void USART6_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); diff --git a/src/main/drivers/transponder_ir.c b/src/main/drivers/transponder_ir.c index 51d47e44e5..8e95ac33bf 100644 --- a/src/main/drivers/transponder_ir.c +++ b/src/main/drivers/transponder_ir.c @@ -38,19 +38,19 @@ uint8_t transponderIrDMABuffer[TRANSPONDER_DMA_BUFFER_SIZE]; volatile uint8_t transponderIrDataTransferInProgress = 0; -void transponderDMAHandler(DMA_Channel_TypeDef *channel) +void transponderDMAHandler(dmaChannelDescriptor_t* descriptor) { - if (DMA_GetFlagStatus(TRANSPONDER_DMA_TC_FLAG)) { + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { transponderIrDataTransferInProgress = 0; - DMA_Cmd(channel, DISABLE); - DMA_ClearFlag(TRANSPONDER_DMA_TC_FLAG); + DMA_Cmd(descriptor->channel, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); } } void transponderIrInit(void) { memset(&transponderIrDMABuffer, 0, TRANSPONDER_DMA_BUFFER_SIZE); - dmaSetHandler(TRANSPONDER_DMA_HANDLER_IDENTIFER, transponderDMAHandler); + dmaSetHandler(TRANSPONDER_DMA_HANDLER_IDENTIFER, transponderDMAHandler, NVIC_PRIO_TRANSPONDER_DMA, 0); transponderIrHardwareInit(); } diff --git a/src/main/drivers/transponder_ir_stm32f30x.c b/src/main/drivers/transponder_ir_stm32f30x.c index d41e3aa8c8..3962e1c999 100644 --- a/src/main/drivers/transponder_ir_stm32f30x.c +++ b/src/main/drivers/transponder_ir_stm32f30x.c @@ -86,7 +86,7 @@ void transponderIrHardwareInit(void) /* configure DMA */ /* DMA clock enable */ - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + //RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); /* DMA1 Channel6 Config */ DMA_DeInit(TRANSPONDER_DMA_CHANNEL); @@ -110,13 +110,6 @@ void transponderIrHardwareInit(void) DMA_ITConfig(TRANSPONDER_DMA_CHANNEL, DMA_IT_TC, ENABLE); - NVIC_InitTypeDef NVIC_InitStructure; - - NVIC_InitStructure.NVIC_IRQChannel = TRANSPONDER_IRQ; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TRANSPONDER_DMA); - NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TRANSPONDER_DMA); - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); } void transponderIrDMAEnable(void) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index c9eb4a59da..a7c09026a3 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -125,7 +125,9 @@ #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 #define MAX7456_SPI_CS_PIN SPI1_NSS_PIN - +#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3 +//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2 // <- Conflicts with WS2811 DMA +#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index cf6eacf4cb..76ca16fe9f 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -114,10 +114,7 @@ #define MAX7456_DMA_CHANNEL_TX DMA2_Channel2 #define MAX7456_DMA_CHANNEL_RX DMA2_Channel1 -#define MAX7456_DMA_TC_FLAG DMA2_FLAG_TC1 -#define MAX7456_DMA_PERIPH_CLOCK RCC_AHBPeriph_DMA2 -#define MAX7456_DMA_IRQ_HANDLER_FUNCTION DMA2_Channel1_IRQHandler -#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_Channel1_IRQn +#define MAX7456_DMA_IRQ_HANDLER_ID DMA2_CH1_HANDLER #define USE_RTC6705 #define RTC6705_SPIDATA_PIN PC15 From d0f060175cda9cf3ca047fbf5f986cec3d827366 Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Fri, 1 Jul 2016 12:10:45 +0200 Subject: [PATCH 037/108] Ignore linker wchar size warnings. --- Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/Makefile b/Makefile index b8c891ef62..e41d2d19e4 100644 --- a/Makefile +++ b/Makefile @@ -600,6 +600,7 @@ LDFLAGS = -lm \ -Wl,-gc-sections,-Map,$(TARGET_MAP) \ -Wl,-L$(LINKER_DIR) \ -Wl,--cref \ + -Wl,--no-wchar-size-warning \ -T$(LD_SCRIPT) ############################################################################### From e498e85e50dde6e712df14e96cd561849a272175 Mon Sep 17 00:00:00 2001 From: SergDoc Date: Fri, 1 Jul 2016 21:53:09 +0300 Subject: [PATCH 038/108] F4BY added --- src/main/target/F4BY/target.c | 104 +++++++++++++++++++++ src/main/target/F4BY/target.h | 159 +++++++++++++++++++++++++++++++++ src/main/target/F4BY/target.mk | 8 ++ 3 files changed, 271 insertions(+) create mode 100644 src/main/target/F4BY/target.c create mode 100644 src/main/target/F4BY/target.h create mode 100644 src/main/target/F4BY/target.mk diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c new file mode 100644 index 0000000000..472d1e8017 --- /dev/null +++ b/src/main/target/F4BY/target.c @@ -0,0 +1,104 @@ + +#include +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + 0xFFFF +}; + +const uint16_t airPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM16 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), + PWM3 | (MAP_TO_PWM_INPUT << 8), + PWM4 | (MAP_TO_PWM_INPUT << 8), + PWM5 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 + PWM15 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S1_IN + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S2_IN + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S3_IN + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S4_IN + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S5_IN + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S6_IN + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S7_IN + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S8_IN + + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S1_OUT + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S2_OUT + { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S3_OUT + { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S4_OUT + { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S5_OUT + { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S6_OUT + { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S7_OUT + { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S8_OUT +}; + diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h new file mode 100644 index 0000000000..c27aa4a386 --- /dev/null +++ b/src/main/target/F4BY/target.h @@ -0,0 +1,159 @@ +/* + * 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 . + */ + +#pragma once +#define TARGET_BOARD_IDENTIFIER "F4BY" + +#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) + +#define USBD_PRODUCT_STRING "Swift-Flyer F4BY" + +#define LED0 PE3 // Blue LED +#define LED1 PE2 // Red LED +#define LED2 PE1 // Blue LED +#define BEEPER PE5 + +#define INVERTER PD3 +#define INVERTER_USART USART6 + + + +// MPU6000 interrupts +#define USE_MPU_DATA_READY_SIGNAL +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) +#define MPU_INT_EXTI PB0 +#define USE_EXTI + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW90_DEG + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW90_DEG + +#define MAG +#define USE_MAG_HMC5883 +#define MAG_HMC5883_ALIGN CW90_DEG + +#define BARO +#define USE_BARO_MS5611 + +#define USE_SDCARD + +#define SDCARD_SPI_INSTANCE SPI3 +#define SDCARD_SPI_CS_PIN PE15 + +// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 +#define SDCARD_DMA_CHANNEL DMA_Channel_0 + +// Performance logging for SD card operations: + +#define USABLE_TIMER_CHANNEL_COUNT 16 + +#define USE_VCP +#define VBUS_SENSING_PIN PA9 + +#define USE_USART1 +#define USART1_RX_PIN PB7 +#define USART1_TX_PIN PB6 +#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 + +#define USE_USART2 +#define USART2_RX_PIN PD6 +#define USART2_TX_PIN PD5 + +#define USE_USART3 +#define USART3_RX_PIN PD9 +#define USART3_TX_PIN PD8 + +#define USE_USART6 +#define USART6_RX_PIN PC7 +#define USART6_TX_PIN PC6 + + +#define SERIAL_PORT_COUNT 5 + +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN NONE + + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN NONE +#define SPI2_SCK_PIN PB3 +#define SPI2_MISO_PIN PB4 +#define SPI2_MOSI_PIN PB5 + + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_2) +#define USE_I2C_PULLUP +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_ADC +//#define BOARD_HAS_VOLTAGE_DIVIDER +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PC1 + + +#define SENSORS_SET (SENSOR_ACC) + + +// alternative defaults for F4BY +//#define F4BY + +#define SPEKTRUM_BIND +// USART6, PC7 +#define BIND_PIN PC7 + +#define HARDWARE_BIND_PLUG +// Hardware bind plug at PB2 (Pin 28) +#define BINDPLUG_PIN PB2 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define BRUSHED_MOTORS +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) + +#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 0xffff +#define TARGET_IO_PORTE 0xffff + +#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) + diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk new file mode 100644 index 0000000000..5093a8df72 --- /dev/null +++ b/src/main/target/F4BY/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c + From 924c891bf1f26000b60b6411882aeb74062b9706 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 14:38:04 +1000 Subject: [PATCH 039/108] Update to LED STRIP to use new IO --- src/main/config/config.c | 4 +- src/main/drivers/light_ws2811strip.c | 16 +- .../drivers/light_ws2811strip_stm32f10x.c | 52 +++--- .../drivers/light_ws2811strip_stm32f30x.c | 61 +++---- .../drivers/light_ws2811strip_stm32f4xx.c | 150 ++++++++++++------ src/main/drivers/pwm_mapping.c | 18 +-- src/main/drivers/timer.c | 12 ++ src/main/drivers/timer.h | 12 +- src/main/drivers/timer_stm32f30x.c | 20 +-- src/main/drivers/timer_stm32f4xx.c | 28 ++-- src/main/io/ledstrip.c | 8 +- src/main/io/ledstrip.h | 2 +- src/main/io/serial_msp.c | 2 +- src/main/scheduler/scheduler_tasks.c | 4 +- src/main/target/ALIENFLIGHTF4/target.h | 8 +- src/main/target/BLUEJAYF4/target.h | 13 ++ src/main/target/BLUEJAYF4/target.mk | 4 +- src/main/target/CC3D/target.h | 9 +- src/main/target/COLIBRI_RACE/i2c_bst.c | 2 +- src/main/target/COLIBRI_RACE/target.h | 9 +- src/main/target/DOGE/target.h | 8 +- src/main/target/EUSTM32F103RC/target.h | 3 - src/main/target/FURYF3/target.h | 8 +- src/main/target/LUX_RACE/target.h | 9 +- src/main/target/MOTOLAB/target.h | 8 +- src/main/target/NAZE/target.h | 3 +- src/main/target/OLIMEXINO/target.h | 6 - src/main/target/OMNIBUS/target.h | 8 +- src/main/target/PIKOBLX/target.h | 8 +- src/main/target/PORT103R/target.h | 3 - src/main/target/REVO/target.h | 2 - src/main/target/REVONANO/target.h | 6 - src/main/target/RMDO/target.h | 8 +- src/main/target/SINGULARITY/target.h | 8 +- src/main/target/SPARKY/target.h | 9 +- src/main/target/SPRACINGF3/target.h | 8 +- src/main/target/SPRACINGF3EVO/target.h | 9 +- src/main/target/SPRACINGF3MINI/target.h | 9 +- src/main/target/STM32F3DISCOVERY/target.h | 8 +- src/main/target/X_RACERSPI/target.h | 8 +- 40 files changed, 277 insertions(+), 296 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 5bcd1e923b..43820350d9 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -848,10 +848,10 @@ void validateAndFixConfig(void) if (featureConfigured(FEATURE_SOFTSERIAL) && ( 0 #ifdef USE_SOFTSERIAL1 - || (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER) + || (WS2811_TIMER == SOFTSERIAL_1_TIMER) #endif #ifdef USE_SOFTSERIAL2 - || (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER) + || (WS2811_TIMER == SOFTSERIAL_2_TIMER) #endif )) { // led strip needs the same timer as softserial diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index 3821350f57..5bd5857b56 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -80,18 +80,9 @@ void setStripColors(const hsvColor_t *colors) } } -void ws2811DMAHandler(DMA_Channel_TypeDef *channel) { - if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) { - ws2811LedDataTransferInProgress = 0; - DMA_Cmd(channel, DISABLE); - DMA_ClearFlag(WS2811_DMA_TC_FLAG); - } -} - void ws2811LedStripInit(void) { memset(&ledStripDMABuffer, 0, WS2811_DMA_BUFFER_SIZE); - dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); ws2811LedStripHardwareInit(); ws2811UpdateStrip(); } @@ -141,12 +132,11 @@ STATIC_UNIT_TESTED void updateLEDDMABuffer(uint8_t componentValue) */ void ws2811UpdateStrip(void) { - static uint32_t waitCounter = 0; static rgbColor24bpp_t *rgb24; - // wait until previous transfer completes - while(ws2811LedDataTransferInProgress) { - waitCounter++; + // don't wait - risk of infinite block, just get an update next time round + if (ws2811LedDataTransferInProgress) { + return; } dmaBufferOffset = 0; // reset buffer memory index diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index b7f1bd4138..40003663d9 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -23,35 +23,41 @@ #include "common/color.h" #include "drivers/light_ws2811strip.h" #include "nvic.h" +#include "io.h" +#include "dma.h" +#include "timer.h" + +#ifdef LED_STRIP + +static IO_t ws2811IO = IO_NONE; +bool ws2811Initialised = false; + +void ws2811DMAHandler(DMA_Channel_TypeDef *channel) +{ + if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(channel, DISABLE); + DMA_ClearFlag(WS2811_DMA_TC_FLAG); + } +} void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; TIM_OCInitTypeDef TIM_OCInitStructure; - GPIO_InitTypeDef GPIO_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; -#ifdef CC3D - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(GPIOB, &GPIO_InitStructure); -#else - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); - - /* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */ - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(GPIOA, &GPIO_InitStructure); -#endif - - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); + + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); +/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ + IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); + + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); + /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ @@ -108,16 +114,20 @@ void ws2811LedStripHardwareInit(void) NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); + ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); } void ws2811LedStripDMAEnable(void) { + if (!ws2811Initialised) + return; + DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(TIM3, 0); TIM_Cmd(TIM3, ENABLE); DMA_Cmd(DMA1_Channel6, ENABLE); } - +#endif \ No newline at end of file diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index fbcc8d3fb0..567fd0b8e5 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -20,51 +20,54 @@ #include -#include "gpio.h" +#include "io.h" #include "nvic.h" #include "common/color.h" #include "drivers/light_ws2811strip.h" +#include "dma.h" +#include "rcc.h" +#include "timer.h" -#ifndef WS2811_GPIO -#define WS2811_GPIO GPIOB -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#ifdef LED_STRIP + +#ifndef WS2811_PIN +#define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER - #endif +static IO_t ws2811IO = IO_NONE; +bool ws2811Initialised = false; + +void ws2811DMAHandler(DMA_Channel_TypeDef *channel) +{ + if (DMA_GetFlagStatus(WS2811_DMA_TC_FLAG)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(channel, DISABLE); + DMA_ClearFlag(WS2811_DMA_TC_FLAG); + } +} + void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; TIM_OCInitTypeDef TIM_OCInitStructure; - GPIO_InitTypeDef GPIO_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; - - RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE); - - GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, WS2811_GPIO_AF); - - /* Configuration alternate function push-pull */ - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = WS2811_PIN; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(WS2811_GPIO, &GPIO_InitStructure); - - - RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE); + + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); + + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); + /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ + IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); + + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; @@ -122,16 +125,20 @@ void ws2811LedStripHardwareInit(void) NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); + ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); } void ws2811LedStripDMAEnable(void) { + if (!ws2811Initialised) + return; + DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(WS2811_TIMER, 0); TIM_Cmd(WS2811_TIMER, ENABLE); DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE); } - +#endif \ No newline at end of file diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index d85f1c5757..7bc139c32e 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -22,64 +22,122 @@ #include "common/color.h" #include "light_ws2811strip.h" +#include "dma.h" #include "nvic.h" +#include "io.h" +#include "system.h" +#include "rcc.h" +#include "timer.h" #ifdef LED_STRIP + +#if !defined(WS2811_PIN) +#define WS2811_PIN PA0 +#define WS2811_TIMER TIM5 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream2 +#define WS2811_DMA_FLAG DMA_FLAG_TCIF2 +#define WS2811_DMA_IT DMA_IT_TCIF2 +#define WS2811_DMA_CHANNEL DMA_Channel_6 +#define WS2811_DMA_IRQ DMA1_Stream2_IRQn +#define WS2811_TIMER_CHANNEL TIM_Channel_1 +#endif + +static IO_t ws2811IO = IO_NONE; +static uint16_t timDMASource = 0; +bool ws2811Initialised = false; + +void ws2811DMAHandler(DMA_Stream_TypeDef *stream) +{ + if (DMA_GetFlagStatus(stream, WS2811_DMA_FLAG)) { + ws2811LedDataTransferInProgress = 0; + DMA_ClearITPendingBit(stream, WS2811_DMA_IT); + DMA_Cmd(stream, DISABLE); + TIM_DMACmd(WS2811_TIMER, timDMASource, DISABLE); + } +} + void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; TIM_OCInitTypeDef TIM_OCInitStructure; - GPIO_InitTypeDef GPIO_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE); - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); - + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz; - GPIO_Init(GPIOA, &GPIO_InitStructure); - - GPIO_PinAFConfig(GPIOA, GPIO_PinSource0, GPIO_AF_TIM5); - - + IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); + // Stop timer - TIM_Cmd(TIM5, DISABLE); + TIM_Cmd(WS2811_TIMER, DISABLE); /* Compute the prescaler value */ - prescalerValue = (uint16_t) (SystemCoreClock / 2 / 84000000) - 1; + prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1; + /* Time base configuration */ TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(TIM5, &TIM_TimeBaseStructure); + TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure); /* PWM1 Mode configuration: Channel1 */ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; + TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set; + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High; + TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; TIM_OCInitStructure.TIM_Pulse = 0; - TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; - TIM_OC1Init(TIM5, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(TIM5, TIM_OCPreload_Enable); + + uint32_t channelAddress = 0; + switch (WS2811_TIMER_CHANNEL) + { + case TIM_Channel_1: + TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC1; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); + TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_2: + TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC2; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); + TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_3: + TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC3; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); + TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_4: + TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC4; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); + TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + } + + TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); + TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE); - TIM_Cmd(TIM5, ENABLE); + TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable); + TIM_Cmd(WS2811_TIMER, ENABLE); + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); /* configure DMA */ - /* DMA1 Channel Config */ - DMA_Cmd(DMA1_Stream2, DISABLE); // disable DMA channel 6 - DMA_DeInit(DMA1_Stream2); + DMA_Cmd(WS2811_DMA_STREAM, DISABLE); + DMA_DeInit(WS2811_DMA_STREAM); DMA_StructInit(&DMA_InitStructure); - DMA_InitStructure.DMA_Channel = DMA_Channel_6; - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&(TIM5->CCR1); + DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL; + DMA_InitStructure.DMA_PeripheralBaseAddr = channelAddress; DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE; @@ -93,38 +151,36 @@ void ws2811LedStripHardwareInit(void) DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull; DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; - DMA_Init(DMA1_Stream2, &DMA_InitStructure); - DMA_ITConfig(DMA1_Stream2, DMA_IT_TC, ENABLE); - DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); // clear DMA1 Channel 6 transfer complete flag + + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); + DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure); + DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE); + DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); + NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Stream2_IRQn; + NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); + ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); } -void DMA1_Stream2_IRQHandler(void) -{ - if (DMA_GetFlagStatus(DMA1_Stream2, DMA_FLAG_TCIF2)) { - ws2811LedDataTransferInProgress = 0; - DMA_Cmd(DMA1_Stream2, DISABLE); - TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE); - DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); - } -} - void ws2811LedStripDMAEnable(void) { - DMA_SetCurrDataCounter(DMA1_Stream2, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred - TIM_SetCounter(TIM5, 0); - DMA_Cmd(DMA1_Stream2, ENABLE); - TIM_DMACmd(TIM5, TIM_DMA_CC1, ENABLE); + if (!ws2811Initialised) + return; + + DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred + TIM_SetCounter(WS2811_TIMER, 0); + DMA_Cmd(WS2811_DMA_STREAM, ENABLE); + TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE); } -#endif + +#endif \ No newline at end of file diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 8d332ba56e..5e797ea2f0 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -157,33 +157,33 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#ifdef LED_STRIP_TIMER +#ifdef WS2811_TIMER // skip LED Strip output if (init->useLEDStrip) { - if (timerHardwarePtr->tim == LED_STRIP_TIMER) + if (timerHardwarePtr->tim == WS2811_TIMER) continue; -#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) - if (CheckGPIOPinSource(timerHardwarePtr->tag, WS2811_GPIO, WS2811_PIN_SOURCE)) +#if defined(STM32F303xC) && defined(WS2811_PIN) + if (timerHardwarePtr->tag == IO_TAG(WS2811_PIN)) continue; #endif } #endif -#ifdef VBAT_ADC_GPIO - if (init->useVbat && CheckGPIOPin(timerHardwarePtr->tag, VBAT_ADC_GPIO, VBAT_ADC_GPIO_PIN)) { +#ifdef VBAT_ADC_PIN + if (init->useVbat && timerHardwarePtr->tag == IO_TAG(VBAT_ADC_PIN)) { continue; } #endif #ifdef RSSI_ADC_GPIO - if (init->useRSSIADC && CheckGPIOPin(timerHardwarePtr->tag, RSSI_ADC_GPIO, RSSI_ADC_GPIO_PIN)) { + if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) { continue; } #endif #ifdef CURRENT_METER_ADC_GPIO - if (init->useCurrentMeterADC && CheckGPIOPin(timerHardwarePtr->tag, CURRENT_METER_ADC_GPIO, CURRENT_METER_ADC_GPIO_PIN)) { + if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) { continue; } #endif @@ -274,7 +274,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) } if (init->useChannelForwarding && !init->airplane) { -#if defined(NAZE) && defined(LED_STRIP_TIMER) +#if defined(NAZE) && defined(WS2811_TIMER) // if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14 if (init->useLEDStrip) { if (timerIndex >= PWM13 && timerIndex <= PWM14) { diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 37067ae254..e168a46dfe 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -151,6 +151,18 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim) return 0; } +#if defined(STM32F3) || defined(STM32F4) +uint8_t timerGPIOAF(TIM_TypeDef *tim) +{ + for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) { + if (timerDefinitions[i].TIMx == tim) { + return timerDefinitions[i].alternateFunction; + } + } + return 0; +} +#endif + void timerNVICConfigure(uint8_t irq) { NVIC_InitTypeDef NVIC_InitStructure; diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index cdc461c690..26078d4517 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -69,6 +69,9 @@ typedef struct timerOvrHandlerRec_s { typedef struct timerDef_s { TIM_TypeDef *TIMx; rccPeriphTag_t rcc; +#if defined(STM32F3) || defined(STM32F4) + uint8_t alternateFunction; +#endif } timerDef_t; typedef struct timerHardware_s { @@ -82,8 +85,11 @@ typedef struct timerHardware_s { uint8_t alternateFunction; #endif } timerHardware_t; -enum {TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_INVERTED = 0x02}; +enum { + TIMER_OUTPUT_ENABLED = 0x01, + TIMER_OUTPUT_INVERTED = 0x02 +}; #ifdef STM32F1 #if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL) @@ -149,3 +155,7 @@ void timerForceOverflow(TIM_TypeDef *tim); void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration rccPeriphTag_t timerRCC(TIM_TypeDef *tim); + +#if defined(STM32F3) || defined(STM32F4) +uint8_t timerGPIOAF(TIM_TypeDef *tim); +#endif diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index 4bce8a70f3..baad756341 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -10,16 +10,16 @@ #include "timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { - { .TIMx = TIM1, .rcc = RCC_APB2(TIM1) }, - { .TIMx = TIM2, .rcc = RCC_APB1(TIM2) }, - { .TIMx = TIM3, .rcc = RCC_APB1(TIM3) }, - { .TIMx = TIM4, .rcc = RCC_APB1(TIM4) }, - { .TIMx = TIM6, .rcc = RCC_APB1(TIM6) }, - { .TIMx = TIM7, .rcc = RCC_APB1(TIM7) }, - { .TIMx = TIM8, .rcc = RCC_APB2(TIM8) }, - { .TIMx = TIM15, .rcc = RCC_APB2(TIM15) }, - { .TIMx = TIM16, .rcc = RCC_APB2(TIM16) }, - { .TIMx = TIM17, .rcc = RCC_APB2(TIM17) }, + { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 }, + { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 }, + { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 }, + { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 }, + { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, + { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, + { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 }, + { .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 }, + { .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 }, + { .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 }, }; diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index 8916a526c0..374e9164b4 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -35,20 +35,20 @@ #define CCMR_Offset ((uint16_t)0x0018) const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { - { .TIMx = TIM1, .rcc = RCC_APB2(TIM1) }, - { .TIMx = TIM2, .rcc = RCC_APB1(TIM2) }, - { .TIMx = TIM3, .rcc = RCC_APB1(TIM3) }, - { .TIMx = TIM4, .rcc = RCC_APB1(TIM4) }, - { .TIMx = TIM5, .rcc = RCC_APB1(TIM5) }, - { .TIMx = TIM6, .rcc = RCC_APB1(TIM6) }, - { .TIMx = TIM7, .rcc = RCC_APB1(TIM7) }, - { .TIMx = TIM8, .rcc = RCC_APB2(TIM8) }, - { .TIMx = TIM9, .rcc = RCC_APB2(TIM9) }, - { .TIMx = TIM10, .rcc = RCC_APB2(TIM10) }, - { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, - { .TIMx = TIM12, .rcc = RCC_APB1(TIM12) }, - { .TIMx = TIM13, .rcc = RCC_APB1(TIM13) }, - { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, + { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 }, + { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 }, + { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 }, + { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 }, + { .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 }, + { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, + { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, + { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 }, + { .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 }, + { .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 }, + { .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 }, + { .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 }, + { .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF_TIM13 }, + { .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF_TIM14 }, }; void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 061f0d798a..863f3a8b6b 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -440,7 +440,7 @@ void updateLedCount(void) } } -void reevalulateLedConfig(void) +void reevaluateLedConfig(void) { updateLedCount(); determineLedStripDimensions(); @@ -534,7 +534,7 @@ bool parseLedStripConfig(uint8_t ledIndex, const char *config) memset(ledConfig, 0, sizeof(ledConfig_t)); } - reevalulateLedConfig(); + reevaluateLedConfig(); return ok; } @@ -1095,7 +1095,7 @@ void applyDefaultLedStripConfig(ledConfig_t *ledConfigs) memset(ledConfigs, 0, MAX_LED_STRIP_LENGTH * sizeof(ledConfig_t)); memcpy(ledConfigs, &defaultLedStripConfig, sizeof(defaultLedStripConfig)); - reevalulateLedConfig(); + reevaluateLedConfig(); } void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse) @@ -1107,7 +1107,7 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse) void ledStripEnable(void) { - reevalulateLedConfig(); + reevaluateLedConfig(); ledStripInitialised = true; ws2811LedStripInit(); diff --git a/src/main/io/ledstrip.h b/src/main/io/ledstrip.h index 5f901e46c8..18915229b7 100644 --- a/src/main/io/ledstrip.h +++ b/src/main/io/ledstrip.h @@ -94,4 +94,4 @@ bool parseColor(uint8_t index, const char *colorConfig); void applyDefaultColors(hsvColor_t *colors, uint8_t colorCount); void ledStripEnable(void); -void reevalulateLedConfig(void); +void reevaluateLedConfig(void); diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 9f2609c0a0..b616605ac3 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1807,7 +1807,7 @@ static bool processInCommand(void) ledConfig->color = read8(); - reevalulateLedConfig(); + reevaluateLedConfig(); } break; #endif diff --git a/src/main/scheduler/scheduler_tasks.c b/src/main/scheduler/scheduler_tasks.c index 721ad27eb8..18299e4904 100644 --- a/src/main/scheduler/scheduler_tasks.c +++ b/src/main/scheduler/scheduler_tasks.c @@ -168,8 +168,8 @@ cfTask_t cfTasks[TASK_COUNT] = { [TASK_LEDSTRIP] = { .taskName = "LEDSTRIP", .taskFunc = taskLedStrip, - .desiredPeriod = 1000000 / 100, // 100 Hz - .staticPriority = TASK_PRIORITY_IDLE, + .desiredPeriod = 1000000 / 10, // 10 Hz + .staticPriority = TASK_PRIORITY_LOW, }, #endif diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index d5122a486c..5c5e7795ff 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -146,16 +146,10 @@ // LED strip configuration using RC5 pin. //#define LED_STRIP -//#define LED_STRIP_TIMER TIM8 //#define USE_LED_STRIP_ON_DMA1_CHANNEL3 -//#define WS2811_GPIO GPIOB -//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -//#define WS2811_GPIO_AF GPIO_AF_3 -//#define WS2811_PIN GPIO_Pin_15 // TIM8_CH3 -//#define WS2811_PIN_SOURCE GPIO_PinSource15 +//#define WS2811_PIN PB15 // TIM8_CH3 //#define WS2811_TIMER TIM8 -//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM8 //#define WS2811_DMA_CHANNEL DMA1_Channel3 //#define WS2811_IRQ DMA1_Channel3_IRQn diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 7160da98f7..8d9d1c633a 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -134,6 +134,19 @@ #define USE_ADC #define VBAT_ADC_PIN PC3 +#define LED_STRIP +// LED Strip can run off Pin 6 (PB1) of the ESC outputs. +#define WS2811_PIN PB1 +#define WS2811_TIMER TIM3 +#define WS2811_TIMER_CHANNEL TIM_Channel_4 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream2 +#define WS2811_DMA_FLAG DMA_FLAG_TCIF2 +#define WS2811_DMA_IT DMA_IT_TCIF2 +#define WS2811_DMA_CHANNEL DMA_Channel_5 +#define WS2811_DMA_IRQ DMA1_Stream2_IRQn + + #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk index 9f23086666..f523965621 100644 --- a/src/main/target/BLUEJAYF4/target.mk +++ b/src/main/target/BLUEJAYF4/target.mk @@ -4,5 +4,7 @@ FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro_spi_mpu6500.c \ drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c + drivers/barometer_ms5611.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f4xx.c diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index a0415670d0..8d6e6afbc3 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -92,12 +92,13 @@ #define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11 #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA0 -#define RSSI_ADC_PIN PB0 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA0 +#define RSSI_ADC_PIN PB0 #define LED_STRIP -#define LED_STRIP_TIMER TIM3 +#define WS2811_PIN PB4 +#define WS2811_TIMER TIM3 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index 10c99ccc01..be0764a03b 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -1403,7 +1403,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand) ledConfig->color = bstRead8(); - reevalulateLedConfig(); + reevaluateLedConfig(); } break; #endif diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 976b287a05..2822227df6 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -122,15 +122,8 @@ #define LED_STRIP #define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG -#define LED_STRIP_TIMER TIM16 - -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource6 +#define WS2811_PIN PA6 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 44a16782b1..7ca509ea28 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -140,15 +140,9 @@ #define LED_STRIP // tqfp48 pin 16 -#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource6 +#define WS2811_PIN PA6 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index d6d916bb28..0869dd46b1 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -102,9 +102,6 @@ #define RSSI_ADC_PIN PA1 #define EXTERNAL1_ADC_PIN PA5 -//#define LED_STRIP -#define LED_STRIP_TIMER TIM3 - #define SPEKTRUM_BIND // USART2, PA3 #define BIND_PIN PA3 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 9075271c1c..db4ddd7457 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -156,16 +156,10 @@ #define CURRENT_METER_ADC_PIN PA2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 6292d2435f..cef9b31b0a 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -95,15 +95,8 @@ #define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP -#define LED_STRIP_TIMER TIM16 - -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource6 +#define WS2811_PIN PA6 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 27bf98691b..183e1326d5 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -126,16 +126,10 @@ #define LED_STRIP #if 1 -#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 -#define WS2811_GPIO GPIOB -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index df73f8e4f2..6de152cb85 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -155,7 +155,8 @@ #define LED_STRIP -#define LED_STRIP_TIMER TIM3 +#define WS2811_TIMER TIM3 +#define WS2811_PIN PA6 #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index b7972ad777..3ff23fd8d3 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -78,18 +78,12 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_2) -// #define SOFT_I2C // enable to test software i2c -// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) -// #define SOFT_I2C_PB67 - #define USE_ADC #define CURRENT_METER_ADC_PIN PB1 #define VBAT_ADC_PIN PA4 #define RSSI_ADC_PIN PA1 #define EXTERNAL1_ADC_PIN PA5 -//#define LED_STRIP -//#define LED_STRIP_TIMER TIM3 // IO - assuming all IOs on smt32f103rb LQFP64 package #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index c9eb4a59da..76d995fce3 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -166,15 +166,9 @@ #define LED_STRIP -#define LED_STRIP_TIMER TIM1 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 8b14570c91..36ee217725 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -94,16 +94,10 @@ #define LED_STRIP #if 1 -#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 -#define WS2811_GPIO GPIOB -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index 64e0b6455c..d5d0850d93 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -115,9 +115,6 @@ #define RSSI_ADC_PIN PA1 #define EXTERNAL1_ADC_PIN PA5 -//#define LED_STRIP -//#define LED_STRIP_TIMER TIM3 - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f103RCT6 in 64pin package diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index d2124e5b28..3a67944b91 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -110,8 +110,6 @@ #define SENSORS_SET (SENSOR_ACC) -//#define LED_STRIP -//#define LED_STRIP_TIMER TIM5 #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125 | FEATURE_RX_SERIAL) diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 6f4a2c4315..14912fffc1 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -85,12 +85,6 @@ #define VBAT_ADC_PIN PA6 #define RSSI_ADC_PIN PA5 - -//#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG) - -//#define LED_STRIP -//#define LED_STRIP_TIMER TIM5 - #define GPS #define BLACKBOX #define TELEMETRY diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 779b8ab6ce..602609862e 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -112,16 +112,10 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index f58dcbe969..4d047843e2 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -98,16 +98,10 @@ #define VBAT_SCALE_DEFAULT 77 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 58101f0b85..0913d0ec16 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -97,16 +97,9 @@ #define LED_STRIP #if 1 // LED strip configuration using PWM motor output pin 5. -#define LED_STRIP_TIMER TIM16 - #define USE_LED_STRIP_ON_DMA1_CHANNEL3 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource6 +#define WS2811_PIN PA6 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 7b2a365a55..840dda225a 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -121,16 +121,10 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index c4a9a04845..4adbe0d563 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -142,16 +142,9 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 - #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 93e2204203..61b4bd9b5e 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -150,15 +150,8 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 - -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 947ad4913a..7664b47e0c 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -146,14 +146,8 @@ #define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP -#define LED_STRIP_TIMER TIM16 -#define WS2811_GPIO GPIOB -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 39c2e6c209..217765adcf 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -124,16 +124,10 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define LED_STRIP_TIMER TIM1 #define USE_LED_STRIP_ON_DMA1_CHANNEL2 -#define WS2811_GPIO GPIOA -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_GPIO_AF GPIO_AF_6 -#define WS2811_PIN GPIO_Pin_8 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PA8 #define WS2811_TIMER TIM1 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 #define WS2811_DMA_CHANNEL DMA1_Channel2 #define WS2811_IRQ DMA1_Channel2_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 From 9ed87c0d9acbe3556460516999fc4c10ee121b41 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 14:38:46 +1000 Subject: [PATCH 040/108] FuryF3 target.c extra item in initialise --- src/main/target/FURYF3/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 4dc593bb3f..cfbced9c16 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -58,7 +58,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - S1 { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2 - { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM6 - S3 + { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3 { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4 { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP From 6df2b6db8d4259576f5cd77726af0f31f2514444 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 17:23:58 +1000 Subject: [PATCH 041/108] Cleaned up USB VCP buffers --- src/main/drivers/io.h | 4 ++++ src/main/io/serial_4way.c | 27 ++++++++++++++------------- src/main/vcpf4/usbd_cdc_vcp.c | 34 ++++++++++++++-------------------- src/main/vcpf4/usbd_cdc_vcp.h | 6 +++--- 4 files changed, 35 insertions(+), 36 deletions(-) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index debc78d950..121e7a0e1d 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -40,18 +40,21 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IO_CONFIG(mode, speed) ((mode) | (speed)) #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_2MHz) +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_25MHz) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_2MHz) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_2MHz) #define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_2MHz) #define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz) #define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz) +#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_25MHz) #elif defined(STM32F3) || defined(STM32F4) #define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) @@ -60,6 +63,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN) #define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) +#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP) #elif defined(UNIT_TEST) diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 6d96a36ec1..81742c96fa 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -44,15 +44,15 @@ #define USE_TXRX_LED #if defined(USE_TXRX_LED) && defined(LED0) -# define RX_LED_OFF LED0_OFF -# define RX_LED_ON LED0_ON -# ifdef LED1 -# define TX_LED_OFF LED1_OFF -# define TX_LED_ON LED1_ON -# else -# define TX_LED_OFF LED0_OFF -# define TX_LED_ON LED0_ON -# endif +#define RX_LED_OFF LED0_OFF +#define RX_LED_ON LED0_ON +#ifdef LED1 +#define TX_LED_OFF LED1_OFF +#define TX_LED_ON LED1_ON +#else +#define TX_LED_OFF LED0_OFF +#define TX_LED_ON LED0_ON +#endif #else # define RX_LED_OFF do {} while(0) # define RX_LED_ON do {} while(0) @@ -120,12 +120,12 @@ void setEscLo(uint8_t selEsc) void setEscInput(uint8_t selEsc) { - IOConfigGPIO(escHardware[selEsc].io, IOCFG_IPU); + IOConfigGPIO(escHardware[selEsc].io, IOCFG_IPU_25); } void setEscOutput(uint8_t selEsc) { - IOConfigGPIO(escHardware[selEsc].io, IOCFG_OUT_PP); + IOConfigGPIO(escHardware[selEsc].io, IOCFG_OUT_PP_25); } // Initialize 4way ESC interface @@ -330,6 +330,7 @@ void esc4wayProcess(serialPort_t *serial) while(!esc4wayExitRequested) { // restart looking for new sequence from host crcIn = 0; + uint8_t esc = readByteCrc(); if(esc != cmd_Local_Escape) continue; // wait for sync character @@ -348,7 +349,6 @@ void esc4wayProcess(serialPort_t *serial) paramBuf[i] = readByteCrc(); readByteCrc(); readByteCrc(); // update input CRC - RX_LED_OFF; outLen = 0; // output handling code will send single zero byte if necessary replyAck = esc4wayAck_OK; @@ -356,6 +356,7 @@ void esc4wayProcess(serialPort_t *serial) if(crcIn != 0) // CRC of correct message == 0 replyAck = esc4wayAck_I_INVALID_CRC; + TX_LED_ON; if (replyAck == esc4wayAck_OK) replyAck = esc4wayProcessCmd(command, addr, paramBuf, inLen, &outLen); @@ -365,8 +366,8 @@ void esc4wayProcess(serialPort_t *serial) outLen = 1; } + RX_LED_OFF; crcOut = 0; - TX_LED_ON; serialBeginWrite(port); writeByteCrc(cmd_Remote_Escape); writeByteCrc(command); diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 93ac1aaa5c..e4681418bb 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -170,20 +170,16 @@ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength) */ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len) { - uint16_t ptr = APP_Rx_ptr_in; - uint32_t i; - - for (i = 0; i < Len; i++) - APP_Rx_Buffer[ptr++ & (APP_RX_DATA_SIZE-1)] = Buf[i]; - - APP_Rx_ptr_in = ptr % APP_RX_DATA_SIZE; - + for (uint32_t i = 0; i < Len; i++) { + APP_Rx_Buffer[APP_Rx_ptr_in] = Buf[i]; + APP_Rx_ptr_in = (APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE; + } return USBD_OK; } uint8_t usbAvailable(void) { - return (usbData.rxBufHead != usbData.rxBufTail); + return (usbData.bufferInPosition != usbData.bufferOutPosition); } /******************************************************************************* @@ -198,8 +194,8 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) uint32_t ch = 0; while (usbAvailable() && ch < len) { - recvBuf[ch] = usbData.rxBuf[usbData.rxBufTail]; - usbData.rxBufTail = (usbData.rxBufTail + 1) % USB_RX_BUFSIZE; + recvBuf[ch] = usbData.buffer[usbData.bufferOutPosition]; + usbData.bufferOutPosition = (usbData.bufferOutPosition + 1) % USB_RX_BUFSIZE; ch++; receiveLength--; } @@ -224,18 +220,16 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) */ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) { - uint16_t ptr = usbData.rxBufHead; - uint32_t i; + __disable_irq(); - for (i = 0; i < Len; i++) - usbData.rxBuf[ptr++ & (USB_RX_BUFSIZE-1)] = Buf[i]; + for (uint32_t i = 0; i < Len; i++) { + usbData.buffer[usbData.bufferInPosition] = Buf[i]; + usbData.bufferInPosition = (usbData.bufferInPosition + 1) % USB_RX_BUFSIZE; + receiveLength++; + } - usbData.rxBufHead = ptr % USB_RX_BUFSIZE; + __enable_irq(); - receiveLength = ((usbData.rxBufHead - usbData.rxBufTail) > 0 ? - (usbData.rxBufHead - usbData.rxBufTail) : - (usbData.rxBufHead + USB_RX_BUFSIZE - usbData.rxBufTail)) % USB_RX_BUFSIZE; - if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index 3ca22aa4ef..7cc0f8febb 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -71,9 +71,9 @@ typedef struct } LINE_CODING; typedef struct { - uint8_t rxBuf[USB_RX_BUFSIZE]; - uint16_t rxBufHead; - uint16_t rxBufTail; + uint8_t buffer[USB_RX_BUFSIZE]; + uint16_t bufferInPosition; + uint16_t bufferOutPosition; } usbStruct_t; From 7d38b510a4929efff1d380569431caccc04dff59 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 17:30:05 +1000 Subject: [PATCH 042/108] Tabs to spaces --- src/main/drivers/timer_stm32f4xx.c | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index 374e9164b4..9b81d936af 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -35,20 +35,20 @@ #define CCMR_Offset ((uint16_t)0x0018) const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { - { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 }, - { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 }, - { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 }, - { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 }, - { .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 }, - { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, - { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, - { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 }, - { .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 }, - { .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 }, - { .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 }, - { .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 }, - { .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF_TIM13 }, - { .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF_TIM14 }, + { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 }, + { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 }, + { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 }, + { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 }, + { .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 }, + { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, + { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, + { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 }, + { .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 }, + { .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 }, + { .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 }, + { .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 }, + { .TIMx = TIM13, .rcc = RCC_APB1(TIM13), GPIO_AF_TIM13 }, + { .TIMx = TIM14, .rcc = RCC_APB1(TIM14), GPIO_AF_TIM14 }, }; void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) From afea1d6123f087b8cb87dc69010144e12abad66d Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 19:37:39 +1000 Subject: [PATCH 043/108] Formatting based on feedback --- .../drivers/light_ws2811strip_stm32f4xx.c | 51 ++++++++-------- src/main/drivers/timer_stm32f4xx.c | 61 +++++++++---------- 2 files changed, 54 insertions(+), 58 deletions(-) diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index 7bc139c32e..f1d04dfbee 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -96,32 +96,31 @@ void ws2811LedStripHardwareInit(void) TIM_OCInitStructure.TIM_Pulse = 0; uint32_t channelAddress = 0; - switch (WS2811_TIMER_CHANNEL) - { - case TIM_Channel_1: - TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure); - timDMASource = TIM_DMA_CC1; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); - TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; - case TIM_Channel_2: - TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); - timDMASource = TIM_DMA_CC2; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); - TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; - case TIM_Channel_3: - TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); - timDMASource = TIM_DMA_CC3; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); - TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; - case TIM_Channel_4: - TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); - timDMASource = TIM_DMA_CC4; - channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); - TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + switch (WS2811_TIMER_CHANNEL) { + case TIM_Channel_1: + TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC1; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); + TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_2: + TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC2; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); + TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_3: + TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC3; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); + TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; + case TIM_Channel_4: + TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); + timDMASource = TIM_DMA_CC4; + channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); + TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); + break; } TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index 9b81d936af..af09f85e1b 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -35,15 +35,15 @@ #define CCMR_Offset ((uint16_t)0x0018) const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { - { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 }, - { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 }, - { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 }, - { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 }, - { .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 }, - { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, - { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, - { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 }, - { .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 }, + { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_TIM1 }, + { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_TIM2 }, + { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_TIM3 }, + { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_TIM4 }, + { .TIMx = TIM5, .rcc = RCC_APB1(TIM5), GPIO_AF_TIM5 }, + { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, + { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, + { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_TIM8 }, + { .TIMx = TIM9, .rcc = RCC_APB2(TIM9), GPIO_AF_TIM9 }, { .TIMx = TIM10, .rcc = RCC_APB2(TIM10), GPIO_AF_TIM10 }, { .TIMx = TIM11, .rcc = RCC_APB2(TIM11), GPIO_AF_TIM11 }, { .TIMx = TIM12, .rcc = RCC_APB1(TIM12), GPIO_AF_TIM12 }, @@ -53,35 +53,32 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) { - uint32_t tmp = 0; + uint32_t tmp = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_OCM(TIM_OCMode)); + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); - tmp = (uint32_t) TIMx; - tmp += CCMR_Offset; + tmp = (uint32_t) TIMx; + tmp += CCMR_Offset; - if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) - { - tmp += (TIM_Channel>>1); + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) { + tmp += (TIM_Channel>>1); - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= TIM_OCMode; - } - else - { - tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } else { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); - } + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } } From a66820382c7f9a6238de3a4a2993813d306bfb6c Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 19:47:37 +1000 Subject: [PATCH 044/108] More formatting (minor cleanup) --- src/main/drivers/timer_stm32f10x.c | 43 ++++++++++----------- src/main/drivers/timer_stm32f30x.c | 60 +++++++++++++++--------------- 2 files changed, 50 insertions(+), 53 deletions(-) diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c index 27e9df381f..09ef0efc8c 100644 --- a/src/main/drivers/timer_stm32f10x.c +++ b/src/main/drivers/timer_stm32f10x.c @@ -57,34 +57,31 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) { - uint32_t tmp = 0; + uint32_t tmp = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_OCM(TIM_OCMode)); + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); - tmp = (uint32_t) TIMx; - tmp += CCMR_Offset; + tmp = (uint32_t) TIMx; + tmp += CCMR_Offset; - if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) - { - tmp += (TIM_Channel>>1); + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) { + tmp += (TIM_Channel>>1); - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= TIM_OCMode; - } - else - { - tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } else { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4) >> (uint16_t)1; - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); - } + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } } diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index baad756341..033aa316c4 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -10,16 +10,16 @@ #include "timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { - { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 }, - { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 }, - { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 }, - { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 }, - { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, - { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, - { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 }, - { .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 }, - { .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 }, - { .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 }, + { .TIMx = TIM1, .rcc = RCC_APB2(TIM1), GPIO_AF_6 }, + { .TIMx = TIM2, .rcc = RCC_APB1(TIM2), GPIO_AF_1 }, + { .TIMx = TIM3, .rcc = RCC_APB1(TIM3), GPIO_AF_2 }, + { .TIMx = TIM4, .rcc = RCC_APB1(TIM4), GPIO_AF_10 }, + { .TIMx = TIM6, .rcc = RCC_APB1(TIM6), 0 }, + { .TIMx = TIM7, .rcc = RCC_APB1(TIM7), 0 }, + { .TIMx = TIM8, .rcc = RCC_APB2(TIM8), GPIO_AF_5 }, + { .TIMx = TIM15, .rcc = RCC_APB2(TIM15), GPIO_AF_9 }, + { .TIMx = TIM16, .rcc = RCC_APB2(TIM16), GPIO_AF_1 }, + { .TIMx = TIM17, .rcc = RCC_APB2(TIM17), GPIO_AF_1 }, }; @@ -58,31 +58,31 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode) { - uint32_t tmp = 0; + uint32_t tmp = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST1_PERIPH(TIMx)); - assert_param(IS_TIM_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_OCM(TIM_OCMode)); + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); - tmp = (uint32_t) TIMx; - tmp += CCMR_OFFSET; + tmp = (uint32_t) TIMx; + tmp += CCMR_OFFSET; - if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) { - tmp += (TIM_Channel>>1); + if ((TIM_Channel == TIM_Channel_1) || (TIM_Channel == TIM_Channel_3)) { + tmp += (TIM_Channel>>1); - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= CCMR_OC13M_MASK; + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC13M_MASK; - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= TIM_OCMode; - } else { - tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1; + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } else { + tmp += (uint32_t)(TIM_Channel - (uint32_t)4) >> (uint32_t)1; - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= CCMR_OC24M_MASK; + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC24M_MASK; - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= (uint32_t)(TIM_OCMode << 8); - } + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint32_t)(TIM_OCMode << 8); + } } From 2a340c137a189cc410ecd13671724a63ec43d075 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 21 Jun 2016 23:45:37 +0100 Subject: [PATCH 045/108] Made headers in target.h files consistent. --- src/main/target/ALIENFLIGHTF3/target.c | 17 ++++++++++++++++- src/main/target/ALIENFLIGHTF4/target.c | 19 ++++++++++++++++++- src/main/target/BLUEJAYF4/target.c | 17 ++++++++++++++++- src/main/target/CC3D/target.c | 17 ++++++++++++++++- src/main/target/CHEBUZZF3/target.c | 18 +++++++++++++++++- src/main/target/CJMCU/target.c | 17 ++++++++++++++++- src/main/target/COLIBRI_RACE/target.c | 17 ++++++++++++++++- src/main/target/DOGE/target.c | 18 +++++++++++++++++- src/main/target/EUSTM32F103RC/target.c | 18 +++++++++++++++++- src/main/target/FURYF3/target.c | 18 +++++++++++++++++- src/main/target/FURYF4/target.c | 18 +++++++++++++++++- src/main/target/IRCFUSIONF3/target.c | 18 +++++++++++++++++- src/main/target/KISSFC/target.c | 18 +++++++++++++++++- src/main/target/LUX_RACE/target.c | 18 +++++++++++++++++- src/main/target/MOTOLAB/target.c | 18 +++++++++++++++++- src/main/target/NAZE/target.c | 18 +++++++++++++++++- src/main/target/OMNIBUS/target.c | 18 +++++++++++++++++- src/main/target/PIKOBLX/target.c | 18 +++++++++++++++++- src/main/target/PORT103R/target.c | 18 +++++++++++++++++- src/main/target/REVO/target.c | 18 +++++++++++++++++- src/main/target/REVONANO/target.c | 2 +- src/main/target/RMDO/target.c | 18 +++++++++++++++++- src/main/target/SINGULARITY/target.c | 18 +++++++++++++++++- src/main/target/SIRINFPV/target.c | 18 +++++++++++++++++- src/main/target/SPARKY/target.c | 18 +++++++++++++++++- src/main/target/SPRACINGF3/target.c | 17 ++++++++++++++++- src/main/target/SPRACINGF3EVO/target.c | 17 ++++++++++++++++- src/main/target/SPRACINGF3MINI/target.c | 17 ++++++++++++++++- src/main/target/STM32F3DISCOVERY/target.c | 17 ++++++++++++++++- 29 files changed, 469 insertions(+), 29 deletions(-) diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index ad85d7b9b9..437bbbf0ab 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index e6024280f5..1aef43a59c 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -1,5 +1,22 @@ +/* + * 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 . + */ + +#include -#include #include #include "drivers/io.h" #include "drivers/pwm_mapping.h" diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index 24df5a7393..f005e5d1a0 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index c685f7e35a..c657054d63 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 132ff783f9..631d83e6aa 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index 926f3efa03..0f8228559e 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c index 675067e068..91b21c8b36 100644 --- a/src/main/target/COLIBRI_RACE/target.c +++ b/src/main/target/COLIBRI_RACE/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index ebd5e6f1f0..c07a925414 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c index 6e1b4ae6b6..b2a0db9a16 100644 --- a/src/main/target/EUSTM32F103RC/target.c +++ b/src/main/target/EUSTM32F103RC/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 4dc593bb3f..c2e230b9af 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c index c5bb0486c0..ac600ea439 100644 --- a/src/main/target/FURYF4/target.c +++ b/src/main/target/FURYF4/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 7207468fae..e31aa3a7b6 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index 60f2a07363..07450ad505 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index e26bb29500..adee79183a 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index b624db7ccf..a89063cc9a 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index 110ce3140a..b7c13f56b2 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index 94250435ab..d895b571ce 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c index b624db7ccf..a89063cc9a 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/PIKOBLX/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/PORT103R/target.c b/src/main/target/PORT103R/target.c index 42ce07beca..8f21b7cbb7 100644 --- a/src/main/target/PORT103R/target.c +++ b/src/main/target/PORT103R/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index b32c5175f0..9a30df53b0 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/REVONANO/target.c b/src/main/target/REVONANO/target.c index 53d4042172..9a579f2bc9 100644 --- a/src/main/target/REVONANO/target.c +++ b/src/main/target/REVONANO/target.c @@ -15,10 +15,10 @@ * along with Cleanflight. If not, see . */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index eaeb18fca4..1bea16f50c 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c index 645bd323f5..8131579519 100644 --- a/src/main/target/SINGULARITY/target.c +++ b/src/main/target/SINGULARITY/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c index dfe1517fb4..0630b527db 100644 --- a/src/main/target/SIRINFPV/target.c +++ b/src/main/target/SIRINFPV/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index d5ecdcc96f..389617278b 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index 122f07bb0a..bf2a06da44 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index 1ac9743d3e..171f6be27a 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index bc0d06cee6..214dab6564 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index dcf2426cee..583c10f66b 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -1,5 +1,20 @@ +/* + * 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 . + */ -#include #include #include From 405d9f051aad299691a60e1a7905d757e8877d7f Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 2 Jul 2016 21:35:52 +1000 Subject: [PATCH 046/108] Added debugging counters --- src/main/io/serial_4way.c | 4 ++-- src/main/io/serial_4way_avrootloader.c | 2 +- src/main/vcpf4/usbd_cdc_vcp.c | 8 +++++--- src/main/vcpf4/usbd_cdc_vcp.h | 2 +- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 81742c96fa..49c5805417 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -359,6 +359,7 @@ void esc4wayProcess(serialPort_t *serial) TX_LED_ON; if (replyAck == esc4wayAck_OK) replyAck = esc4wayProcessCmd(command, addr, paramBuf, inLen, &outLen); + RX_LED_OFF; // send single '\0' byte is output when length is zero (len ==0 -> 256 bytes) if(!outLen) { @@ -366,7 +367,6 @@ void esc4wayProcess(serialPort_t *serial) outLen = 1; } - RX_LED_OFF; crcOut = 0; serialBeginWrite(port); writeByteCrc(cmd_Remote_Escape); @@ -374,7 +374,7 @@ void esc4wayProcess(serialPort_t *serial) writeByteCrc(addr >> 8); writeByteCrc(addr & 0xff); writeByteCrc(outLen & 0xff); // only low byte is send, 0x00 -> 256B - for(int i = 0; i < outLen; i++) + for(int i = 0; i < outLen % 0x100; i++) writeByteCrc(paramBuf[i]); writeByteCrc(replyAck); writeByte(crcOut >> 8); diff --git a/src/main/io/serial_4way_avrootloader.c b/src/main/io/serial_4way_avrootloader.c index efb4610268..01a598e8b2 100644 --- a/src/main/io/serial_4way_avrootloader.c +++ b/src/main/io/serial_4way_avrootloader.c @@ -238,7 +238,7 @@ void BL_SendCMDRunRestartBootloader(void) static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr { // skip if adr == 0xFFFF - if((pMem->addr == 0xffff)) + if(pMem->addr == 0xffff) return 1; uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->addr >> 8, pMem->addr & 0xff }; BL_SendBuf(sCMD, sizeof(sCMD), true); diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index e4681418bb..8b789fa48f 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -218,18 +218,20 @@ uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) * @param Len: Number of data received (in bytes) * @retval Result of the opeartion: USBD_OK if all operations are OK else VCP_FAIL */ +static uint32_t rxTotalBytes = 0; +static uint32_t rxPackets = 0; + static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) { - __disable_irq(); + rxPackets++; for (uint32_t i = 0; i < Len; i++) { usbData.buffer[usbData.bufferInPosition] = Buf[i]; usbData.bufferInPosition = (usbData.bufferInPosition + 1) % USB_RX_BUFSIZE; receiveLength++; + rxTotalBytes++; } - __enable_irq(); - if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index 7cc0f8febb..df1e29001c 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -34,7 +34,7 @@ #include "usbd_usr.h" #include "usbd_desc.h" -#define USB_RX_BUFSIZE 1024 +#define USB_RX_BUFSIZE 2048 __ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END; From f2122e88d9e308ff778bcf333407b1ec1ab1cbd6 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 2 Jul 2016 12:53:47 +0100 Subject: [PATCH 047/108] Tidied whitespace in target files --- src/main/target/ALIENFLIGHTF3/target.c | 29 +++--- src/main/target/ALIENFLIGHTF4/target.c | 104 +++++++++++----------- src/main/target/CC3D/target.c | 14 +-- src/main/target/LUX_RACE/target.c | 12 +-- src/main/target/NAZE/target.c | 12 +-- src/main/target/REVO/target.c | 14 +-- src/main/target/STM32F3DISCOVERY/target.c | 40 ++++----- 7 files changed, 108 insertions(+), 117 deletions(-) diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 437bbbf0ab..57fc417638 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -24,16 +24,16 @@ const uint16_t multiPPM[] = { PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15 - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15 - PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 - PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2 + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15 + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM1 + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM17 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM3 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM2 0xFFFF }; @@ -63,10 +63,7 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // // 6 x 3 pin headers - // - { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR @@ -74,20 +71,14 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - // // 6 pin header - // - // PWM7-10 { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N - // // PPM PORT - Also USART2 RX (AF5) - // - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index 1aef43a59c..efedb56689 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -22,70 +22,70 @@ #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { - PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3 - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4 - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5 - PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6 - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3 + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4 + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5 + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6 + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; const uint16_t multiPWM[] = { - PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 - PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2 - PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3 - PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4 - PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5 - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3 - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4 - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5 - PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6 + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2 + PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3 + PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4 + PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5 + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 or #1 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #2 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #5 or #3 + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #6 or #4 + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #7 or #5 + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8 or #6 0xFFFF }; const uint16_t airPPM[] = { - PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 - PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 - PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 - PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 - PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6 - PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // servo #7 - PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 - PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #9 - PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6 + PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // servo #7 + PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 + PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #9 + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10 0xFFFF }; const uint16_t airPWM[] = { - PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 - PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2 - PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3 - PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4 - PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5 - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 - PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 - PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 - PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 - PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6 + PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1 + PWM2 | (MAP_TO_PWM_INPUT << 8), // input #2 + PWM3 | (MAP_TO_PWM_INPUT << 8), // input #3 + PWM4 | (MAP_TO_PWM_INPUT << 8), // input #4 + PWM5 | (MAP_TO_PWM_INPUT << 8), // input #5 + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 + PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 + PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #6 0xFFFF }; diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index c657054d63..a870de9e24 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -23,16 +23,16 @@ const uint16_t multiPPM[] = { PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index adee79183a..91b21c8b36 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -72,12 +72,12 @@ const uint16_t airPWM[] = { PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index b7c13f56b2..7116b53551 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -23,16 +23,16 @@ const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 9a30df53b0..03f60516d4 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -23,17 +23,17 @@ const uint16_t multiPPM[] = { PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 583c10f66b..1712bebae2 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -23,16 +23,16 @@ const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed 0xFFFF }; @@ -45,27 +45,27 @@ const uint16_t multiPWM[] = { PWM6 | (MAP_TO_PWM_INPUT << 8), PWM7 | (MAP_TO_PWM_INPUT << 8), PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed) + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 0xFFFF }; const uint16_t airPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 PWM12 | (MAP_TO_SERVO_OUTPUT << 8), PWM13 | (MAP_TO_SERVO_OUTPUT << 8), - PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 - PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 PWM6 | (MAP_TO_SERVO_OUTPUT << 8), PWM7 | (MAP_TO_SERVO_OUTPUT << 8), - PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 0xFFFF }; @@ -78,12 +78,12 @@ const uint16_t airPWM[] = { PWM6 | (MAP_TO_PWM_INPUT << 8), PWM7 | (MAP_TO_PWM_INPUT << 8), PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 - PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 PWM12 | (MAP_TO_SERVO_OUTPUT << 8), PWM13 | (MAP_TO_SERVO_OUTPUT << 8), - PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 + PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 0xFFFF }; From 2123a758e7e55223ac7b306f1c276b100d81ad7c Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 2 Jul 2016 15:23:19 +0100 Subject: [PATCH 048/108] Allowed setting of default serial rx in target.h --- src/main/config/config.c | 24 ++++++++---------------- src/main/target/ALIENFLIGHTF3/target.h | 2 +- src/main/target/COLIBRI_RACE/target.h | 6 ++++-- src/main/target/KISSFC/target.h | 3 ++- src/main/target/NAZE/target.h | 1 + src/main/target/OLIMEXINO/target.c | 18 +++++++++++++++++- src/main/target/SINGULARITY/target.h | 6 +++--- 7 files changed, 36 insertions(+), 24 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 5bcd1e923b..755598e4d7 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -645,7 +645,13 @@ static void resetConf(void) masterConfig.blackbox_rate_denom = 1; #endif // BLACKBOX - + +#ifdef SERIALRX_UART + if (featureConfigured(FEATURE_RX_SERIAL)) { + masterConfig.serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL; + } +#endif + // alternative defaults settings for COLIBRI RACE targets #if defined(COLIBRI_RACE) masterConfig.escAndServoConfig.minthrottle = 1025; @@ -660,11 +666,6 @@ static void resetConf(void) #if defined(ALIENFLIGHT) featureClear(FEATURE_ONESHOT125); -#ifdef ALIENFLIGHTF1 - masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL; -#else - masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; -#endif #ifdef ALIENFLIGHTF3 masterConfig.mag_hardware = MAG_NONE; // disabled by default #endif @@ -688,11 +689,6 @@ static void resetConf(void) masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif #endif -#if defined(SINGULARITY) - // alternative defaults settings for SINGULARITY target - masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; -#endif - // copy first profile into remaining profile for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); @@ -901,15 +897,11 @@ void validateAndFixConfig(void) #if defined(COLIBRI_RACE) masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP; - if(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) { + if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) { featureClear(FEATURE_RX_PARALLEL_PWM); featureClear(FEATURE_RX_MSP); featureSet(FEATURE_RX_PPM); } - if(featureConfigured(FEATURE_RX_SERIAL)) { - masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; - //masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS; - } #endif useRxConfig(&masterConfig.rxConfig); diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index a5d1b042f3..4cd3d955cb 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -117,7 +117,6 @@ #define USE_ADC #define ADC_INSTANCE ADC2 -//#define BOARD_HAS_VOLTAGE_DIVIDER #define VBAT_ADC_PIN PA4 #define VBAT_SCALE_DEFAULT 20 @@ -133,6 +132,7 @@ #define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 +#define SERIALRX_UART SERIAL_PORT_USART3 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 976b287a05..449a65e26c 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -113,7 +113,6 @@ #define USE_ADC #define ADC_INSTANCE ADC1 -#define BOARD_HAS_VOLTAGE_DIVIDER #define VBAT_ADC_PIN PC0 #define CURRENT_METER_ADC_PIN PC1 #define RSSI_ADC_PIN PC2 @@ -144,7 +143,10 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_VBAT +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 9095ef7013..d5679d6f27 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -81,7 +81,8 @@ #define DEFAULT_FEATURES FEATURE_VBAT #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS; +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 #define SPEKTRUM_BIND #define BIND_PIN PB4 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index df73f8e4f2..1bc1ded34a 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -180,6 +180,7 @@ #define DEFAULT_FEATURES FEATURE_MOTOR_STOP #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 +#define SERIALRX_UART SERIAL_PORT_USART2 #define HARDWARE_BIND_PLUG // Hardware bind plug at PB5 (Pin 41) diff --git a/src/main/target/OLIMEXINO/target.c b/src/main/target/OLIMEXINO/target.c index 1b75af4224..ea20267b3c 100644 --- a/src/main/target/OLIMEXINO/target.c +++ b/src/main/target/OLIMEXINO/target.c @@ -1,8 +1,24 @@ +/* + * 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 . + */ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index f58dcbe969..814b724205 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -91,7 +91,6 @@ #define M25P16_SPI_INSTANCE SPI2 #define USE_ADC -#define BOARD_HAS_VOLTAGE_DIVIDER #define ADC_INSTANCE ADC2 #define VBAT_ADC_PIN PB2 @@ -115,8 +114,9 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES FEATURE_BLACKBOX +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART3 #define SPEKTRUM_BIND // USART2, PA15 From 8ee2e4f739b005f5850b06ff93942a8f3f984a13 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 2 Jul 2016 15:31:00 +0100 Subject: [PATCH 049/108] Updated VBAT scale --- src/main/target/KISSFC/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index d5679d6f27..260a2bc57f 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -73,7 +73,7 @@ #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_ADC -#define VBAT_SCALE_DEFAULT 164 +#define VBAT_SCALE_DEFAULT 160 #define ADC_INSTANCE ADC1 #define VBAT_ADC_PIN PA0 //#define CURRENT_METER_ADC_PIN PA5 From 816c5d1b8b060bf7b62b931f2b71a637a9392fe6 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 2 Jul 2016 21:14:56 +0100 Subject: [PATCH 050/108] Fixed Alien F4 serial RX UART. --- src/main/target/ALIENFLIGHTF4/target.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index d5122a486c..2481ea6974 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -176,6 +176,7 @@ #define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048 +#define SERIALRX_UART SERIAL_PORT_USART3 #define USE_SERIAL_4WAY_BLHELI_INTERFACE From 72a6e701eb2bb0af06931807d50a9081c85ab4a6 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 3 Jul 2016 07:44:35 +1000 Subject: [PATCH 051/108] Fixed build issue for F1, and added dfu CLI command (for restart in DFU mode) --- src/main/drivers/io.h | 2 -- src/main/drivers/system.h | 1 + src/main/drivers/system_stm32f10x.c | 8 +++++++- src/main/drivers/system_stm32f30x.c | 9 ++++++++- src/main/drivers/system_stm32f4xx.c | 15 +++++++++++++++ src/main/io/serial_4way.c | 4 ++-- src/main/io/serial_cli.c | 24 +++++++++++++++++++++--- 7 files changed, 54 insertions(+), 9 deletions(-) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 121e7a0e1d..315560e430 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -40,14 +40,12 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IO_CONFIG(mode, speed) ((mode) | (speed)) #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_2MHz) -#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_25MHz) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_2MHz) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_2MHz) #define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_2MHz) #define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz) #define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz) -#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_25MHz) #elif defined(STM32F3) || defined(STM32F4) diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 92e17f8a82..c6d58aa744 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -42,6 +42,7 @@ void systemReset(void); void systemResetToBootloader(void); bool isMPUSoftReset(void); void cycleCounterInit(void); +void checkForBootLoaderRequest(void); void enableGPIOPowerUsageAndNoiseReductions(void); // current crystal frequency - 8 or 12MHz diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index 4ad526850a..3e59fe7342 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -37,7 +37,8 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) { +void systemResetToBootloader(void) +{ // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC @@ -68,6 +69,8 @@ bool isMPUSoftReset(void) void systemInit(void) { + checkForBootLoaderRequest(); + SetSysClock(false); #ifdef CC3D @@ -110,3 +113,6 @@ void systemInit(void) SysTick_Config(SystemCoreClock / 1000); } +void checkForBootLoaderRequest(void) +{ +} \ No newline at end of file diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index 7e58ab061a..ee8aef1a0e 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -35,7 +35,8 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) { +void systemResetToBootloader(void) +{ // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC @@ -82,6 +83,8 @@ bool isMPUSoftReset(void) void systemInit(void) { + checkForBootLoaderRequest(); + // Enable FPU SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2)); SetSysClock(); @@ -102,3 +105,7 @@ void systemInit(void) // SysTick SysTick_Config(SystemCoreClock / 1000); } + +void checkForBootLoaderRequest(void) +{ +} diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index f0042026f9..697b2b743d 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -169,6 +169,8 @@ bool isMPUSoftReset(void) void systemInit(void) { + checkForBootLoaderRequest(); + SetSysClock(); // Configure NVIC preempt/priority groups @@ -194,3 +196,16 @@ void systemInit(void) SysTick_Config(SystemCoreClock / 1000); } +void(*bootJump)(void); +void checkForBootLoaderRequest(void) +{ + __enable_irq(); + if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { + *((uint32_t *)0x2001FFFC) = 0x0; + __set_MSP(0x20001000); + + bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); + bootJump(); + while (1); + } +} \ No newline at end of file diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 49c5805417..bcea2f8a1e 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -120,12 +120,12 @@ void setEscLo(uint8_t selEsc) void setEscInput(uint8_t selEsc) { - IOConfigGPIO(escHardware[selEsc].io, IOCFG_IPU_25); + IOConfigGPIO(escHardware[selEsc].io, IOCFG_IPU); } void setEscOutput(uint8_t selEsc) { - IOConfigGPIO(escHardware[selEsc].io, IOCFG_OUT_PP_25); + IOConfigGPIO(escHardware[selEsc].io, IOCFG_OUT_PP); } // Initialize 4way ESC interface diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index a51f828eda..e160869df0 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -112,6 +112,7 @@ static void cliRxFail(char *cmdline); static void cliAdjustmentRange(char *cmdline); static void cliMotorMix(char *cmdline); static void cliDefaults(char *cmdline); +void cliDfu(char *cmdLine); static void cliDump(char *cmdLine); void cliDumpProfile(uint8_t profileIndex); void cliDumpRateProfile(uint8_t rateProfileIndex) ; @@ -122,6 +123,7 @@ static void cliPlaySound(char *cmdline); static void cliProfile(char *cmdline); static void cliRateProfile(char *cmdline); static void cliReboot(void); +static void cliRebootEx(bool bootLoader); static void cliSave(char *cmdline); static void cliSerial(char *cmdline); #ifndef SKIP_SERIAL_PASSTHROUGH @@ -263,8 +265,8 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor), #endif CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults), - CLI_COMMAND_DEF("dump", "dump configuration", - "[master|profile]", cliDump), + CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu), + CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump), CLI_COMMAND_DEF("exit", NULL, NULL, cliExit), CLI_COMMAND_DEF("feature", "configure features", "list\r\n" @@ -2564,10 +2566,19 @@ static void cliRateProfile(char *cmdline) { static void cliReboot(void) { - cliPrint("\r\nRebooting"); + cliRebootEx(false); +} + +static void cliRebootEx(bool bootLoader) +{ + cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); stopMotors(); + if (bootLoader) { + systemResetToBootloader(); + return; + } systemReset(); } @@ -3107,6 +3118,13 @@ static void cliResource(char *cmdline) } } +void cliDfu(char *cmdLine) +{ + UNUSED(cmdLine); + cliPrint("\r\nRestarting in DFU mode"); + cliRebootEx(true); +} + void cliInit(serialConfig_t *serialConfig) { UNUSED(serialConfig); From f499041c8e16476459a911902c8c046e6c17f355 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 3 Jul 2016 08:00:21 +1000 Subject: [PATCH 052/108] STM32F4: execute extra enable irq on startup only if rebooting into DFU --- src/main/drivers/system_stm32f4xx.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 697b2b743d..53f3767a5e 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -199,9 +199,11 @@ void systemInit(void) void(*bootJump)(void); void checkForBootLoaderRequest(void) { - __enable_irq(); if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { + *((uint32_t *)0x2001FFFC) = 0x0; + + __enable_irq(); __set_MSP(0x20001000); bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); From 801add3ce39a3a3a3174c0abef0623b918c3d8fb Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Sat, 2 Jul 2016 17:14:08 -0700 Subject: [PATCH 053/108] Fix F4 targets --- src/main/drivers/dma.h | 3 +-- src/main/drivers/dma_stm32f4xx.c | 29 ++++++++++++------------ src/main/drivers/serial_uart_stm32f4xx.c | 5 ++-- 3 files changed, 19 insertions(+), 18 deletions(-) diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 345c7b2ed8..e0bbdfd12b 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -20,7 +20,6 @@ struct dmaChannelDescriptor_s; typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor); #ifdef STM32F4 -typedef void(*dmaCallbackHandlerFuncPtr)(DMA_Stream_TypeDef *stream); typedef enum { DMA1_ST1_HANDLER = 0, @@ -55,7 +54,7 @@ typedef struct dmaChannelDescriptor_s { dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ } -#define DMA_CLEAR_FLAG(d, flag) d->flagsShift > 31 ? d->dma->HIFCR = (flag << (d->flagsShift - 32)) : d->dma->LIFCR = (flag << d->flagsShift) +#define DMA_CLEAR_FLAG(d, flag) if(d->flagsShift > 31) d->dma->HIFCR = (flag << (d->flagsShift - 32)); else d->dma->LIFCR = (flag << d->flagsShift) #define DMA_GET_FLAG_STATUS(d, flag) (d->flagsShift > 31 ? d->dma->HISR & (flag << (d->flagsShift - 32)): d->dma->LISR & (flag << d->flagsShift)) diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index 3f57dfd985..4661864867 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -53,18 +53,18 @@ static dmaChannelDescriptor_t dmaDescriptors[] = { /* * DMA IRQ Handlers */ -DEFINE_DMA_IRQ_HANDLER(1, 1, DMA1_CH1_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 2, DMA1_CH2_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 3, DMA1_CH3_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 4, DMA1_CH4_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_CH5_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_CH6_HANDLER) -DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_CH7_HANDLER) -DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_CH1_HANDLER) -DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_CH2_HANDLER) -DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_CH3_HANDLER) -DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER) -DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 1, DMA1_ST1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 2, DMA1_ST2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 3, DMA1_ST3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 4, DMA1_ST4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 5, DMA1_ST5_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 6, DMA1_ST6_HANDLER) +DEFINE_DMA_IRQ_HANDLER(1, 7, DMA1_ST7_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 1, DMA2_ST1_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 2, DMA2_ST2_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 3, DMA2_ST3_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_ST4_HANDLER) +DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER) void dmaInit(void) @@ -72,12 +72,13 @@ void dmaInit(void) // TODO: Do we need this? } -void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority) +void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam) { NVIC_InitTypeDef NVIC_InitStructure; - RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].periphClk, ENABLE); + RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rrc, ENABLE); dmaDescriptors[identifier].irqHandlerCallback = callback; + dmaDescriptors[identifier].userParam = userParam; NVIC_InitStructure.NVIC_IRQChannel = dmaDescriptors[identifier].irqN; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(priority); diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index d8c8ee5df5..4d9bf82dbd 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -25,6 +25,7 @@ #include "io.h" #include "rcc.h" #include "nvic.h" +#include "dma.h" #include "serial.h" #include "serial_uart.h" @@ -278,9 +279,9 @@ static void handleUsartTxDma(uartPort_t *s) s->txDMAEmpty = true; } -void dmaIRQHandler(dmaChannelDescriptor_t descriptor) +void dmaIRQHandler(dmaChannelDescriptor_t* descriptor) { - uartPort_t *s = &((uartDevice_t*)(descriptor->userParam)->port); + uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port); if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); From 74d20a276f7156538bbecba65375447a1ed4bf78 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 29 Jun 2016 15:02:29 +0100 Subject: [PATCH 054/108] Made filter naming, parameters and state consistent --- src/main/common/filter.c | 91 +++++++++++++++++---------------- src/main/common/filter.h | 26 ++++++---- src/main/flight/imu.c | 1 - src/main/flight/mixer.c | 6 +-- src/main/flight/pid.c | 12 ++--- src/main/sensors/acceleration.c | 19 +++---- src/main/sensors/battery.c | 15 +++--- src/main/sensors/gyro.c | 6 +-- 8 files changed, 93 insertions(+), 83 deletions(-) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 21fd2948f8..d059fe882f 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -17,76 +17,81 @@ #include #include -#include #include -#include "common/axis.h" #include "common/filter.h" #include "common/maths.h" -#define M_LN2_FLOAT 0.69314718055994530942f -#define M_PI_FLOAT 3.14159265358979323846f +#define M_LN2_FLOAT 0.69314718055994530942f +#define M_PI_FLOAT 3.14159265358979323846f #define BIQUAD_BANDWIDTH 1.9f /* bandwidth in octaves */ #define BIQUAD_Q 1.0f / sqrtf(2.0f) /* quality factor - butterworth*/ -// PT1 Low Pass filter (when no dT specified it will be calculated from the cycleTime) -float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dT) { +// PT1 Low Pass filter - // Pre calculate and store RC - if (!filter->RC) { - filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut ); - } +void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT) +{ + filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut ); + filter->dT = dT; +} - filter->state = filter->state + dT / (filter->RC + dT) * (input - filter->state); +float pt1FilterApply(pt1Filter_t *filter, float input) +{ + filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state); + return filter->state; +} + +float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT) +{ + // Pre calculate and store RC + if (!filter->RC) { + filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut ); + filter->dT = dT; + } + + filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state); return filter->state; } /* sets up a biquad Filter */ -void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate) +void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate) { - float sampleRate; + const float sampleRate = 1 / ((float)refreshRate * 0.000001f); - sampleRate = 1 / ((float)refreshRate * 0.000001f); - - float omega, sn, cs, alpha; - float a0, a1, a2, b0, b1, b2; - - /* setup variables */ - omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate; - sn = sinf(omega); - cs = cosf(omega); + // setup variables + const float omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate; + const float sn = sinf(omega); + const float cs = cosf(omega); //this is wrong, should be hyperbolic sine //alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn); - alpha = sn / (2 * BIQUAD_Q); + const float alpha = sn / (2 * BIQUAD_Q); - b0 = (1 - cs) / 2; - b1 = 1 - cs; - b2 = (1 - cs) / 2; - a0 = 1 + alpha; - a1 = -2 * cs; - a2 = 1 - alpha; + const float b0 = (1 - cs) / 2; + const float b1 = 1 - cs; + const float b2 = (1 - cs) / 2; + const float a0 = 1 + alpha; + const float a1 = -2 * cs; + const float a2 = 1 - alpha; - /* precompute the coefficients */ - newState->b0 = b0 / a0; - newState->b1 = b1 / a0; - newState->b2 = b2 / a0; - newState->a1 = a1 / a0; - newState->a2 = a2 / a0; + // precompute the coefficients + filter->b0 = b0 / a0; + filter->b1 = b1 / a0; + filter->b2 = b2 / a0; + filter->a1 = a1 / a0; + filter->a2 = a2 / a0; - /* zero initial samples */ - newState->d1 = newState->d2 = 1; + // zero initial samples + filter->d1 = filter->d2 = 0; } /* Computes a biquad_t filter on a sample */ -float applyBiQuadFilter(float sample, biquad_t *state) //direct form 2 transposed +float biquadFilterApply(biquadFilter_t *filter, float input) { - float result; - - result = state->b0 * sample + state->d1; - state->d1 = state->b1 * sample - state->a1 * result + state->d2; - state->d2 = state->b2 * sample - state->a2 * result; + const float result = filter->b0 * input + filter->d1; + filter->d1 = filter->b1 * input - filter->a1 * result + filter->d2; + filter->d2 = filter->b2 * input - filter->a2 * result; return result; } diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 809063f4b0..66fcb53bb0 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -17,20 +17,26 @@ #define DELTA_MAX_SAMPLES 12 -typedef struct filterStatePt1_s { - float state; - float RC; - float constdT; -} filterStatePt1_t; +typedef struct pt1Filter_s { + float state; + float RC; + float dT; +} pt1Filter_t; /* this holds the data required to update samples thru a filter */ -typedef struct biquad_s { +typedef struct biquadFilter_s { float b0, b1, b2, a1, a2; float d1, d2; -} biquad_t; +} biquadFilter_t; + + +void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate); +float biquadFilterApply(biquadFilter_t *filter, float input); + +void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT); +float pt1FilterApply(pt1Filter_t *filter, float input); +float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT); -float applyBiQuadFilter(float sample, biquad_t *state); -float filterApplyPt1(float input, filterStatePt1_t *filter, float f_cut, float dt); int32_t filterApplyAverage(int32_t input, uint8_t averageCount, int32_t averageState[DELTA_MAX_SAMPLES]); float filterApplyAveragef(float input, uint8_t averageCount, float averageState[DELTA_MAX_SAMPLES]); -void BiQuadNewLpf(float filterCutFreq, biquad_t *newState, uint32_t refreshRate); + diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 2e200cff1f..d885d30eaa 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -28,7 +28,6 @@ #include "debug.h" #include "common/axis.h" -#include "common/filter.h" #include "drivers/system.h" #include "drivers/sensor.h" diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index adc0145ba9..b5da4a0170 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -946,7 +946,7 @@ void filterServos(void) #ifdef USE_SERVOS static int16_t servoIdx; static bool servoFilterIsSet; - static biquad_t servoFilterState[MAX_SUPPORTED_SERVOS]; + static biquadFilter_t servoFilter[MAX_SUPPORTED_SERVOS]; #if defined(MIXER_DEBUG) uint32_t startTime = micros(); @@ -955,11 +955,11 @@ void filterServos(void) if (mixerConfig->servo_lowpass_enable) { for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) { if (!servoFilterIsSet) { - BiQuadNewLpf(mixerConfig->servo_lowpass_freq, &servoFilterState[servoIdx], targetPidLooptime); + biquadFilterInit(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime); servoFilterIsSet = true; } - servo[servoIdx] = lrintf(applyBiQuadFilter((float) servo[servoIdx], &servoFilterState[servoIdx])); + servo[servoIdx] = lrintf(biquadFilterApply(&servoFilter[servoIdx], (float)servo[servoIdx])); // Sanity check servo[servoIdx] = constrain(servo[servoIdx], servoConf[servoIdx].min, servoConf[servoIdx].max); } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 91ccbc2d84..b0dee87496 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -112,8 +112,8 @@ float getdT (void) const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; -static filterStatePt1_t deltaFilterState[3]; -static filterStatePt1_t yawFilterState; +static pt1Filter_t deltaFilter[3]; +static pt1Filter_t yawFilter; #ifndef SKIP_PID_LUXFLOAT static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, @@ -205,7 +205,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat //-----calculate D-term if (axis == YAW) { - if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); + if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT()); axisPID[axis] = lrintf(PTerm + ITerm); @@ -230,7 +230,7 @@ static void pidFloat(const pidProfile_t *pidProfile, uint16_t max_angle_inclinat delta *= (1.0f / getdT()); // Filter delta - if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1(delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT()); + if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], delta, pidProfile->dterm_lpf_hz, getdT()); DTerm = constrainf(luxDTermScale * delta * (float)pidProfile->D8[axis] * tpaFactor, -300.0f, 300.0f); @@ -344,7 +344,7 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin //-----calculate D-term if (axis == YAW) { - if (pidProfile->yaw_lpf_hz) PTerm = filterApplyPt1(PTerm, &yawFilterState, pidProfile->yaw_lpf_hz, getdT()); + if (pidProfile->yaw_lpf_hz) PTerm = pt1FilterApply4(&yawFilter, PTerm, pidProfile->yaw_lpf_hz, getdT()); axisPID[axis] = PTerm + ITerm; @@ -369,7 +369,7 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin delta = (delta * ((uint16_t) 0xFFFF / ((uint16_t)targetPidLooptime >> 4))) >> 5; // Filter delta - if (pidProfile->dterm_lpf_hz) delta = filterApplyPt1((float)delta, &deltaFilterState[axis], pidProfile->dterm_lpf_hz, getdT()); + if (pidProfile->dterm_lpf_hz) delta = pt1FilterApply4(&deltaFilter[axis], (float)delta, pidProfile->dterm_lpf_hz, getdT()); DTerm = (delta * pidProfile->D8[axis] * PIDweight[axis] / 100) >> 8; diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index d79eb2e14b..da86d37eb4 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -47,7 +47,6 @@ uint32_t accTargetLooptime; static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. extern uint16_t InflightcalibratingA; -extern bool AccInflightCalibrationArmed; extern bool AccInflightCalibrationMeasurementDone; extern bool AccInflightCalibrationSavetoEEProm; extern bool AccInflightCalibrationActive; @@ -55,7 +54,7 @@ extern bool AccInflightCalibrationActive; static flightDynamicsTrims_t *accelerationTrims; static float accLpfCutHz = 0; -static biquad_t accFilterState[XYZ_AXIS_COUNT]; +static biquadFilter_t accFilter[XYZ_AXIS_COUNT]; static bool accFilterInitialised = false; void accSetCalibrationCycles(uint16_t calibrationCyclesRequired) @@ -87,9 +86,8 @@ void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims) void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) { static int32_t a[3]; - int axis; - for (axis = 0; axis < 3; axis++) { + for (int axis = 0; axis < 3; axis++) { // Reset a[axis] at start of calibration if (isOnFirstAccelerationCalibrationCycle()) @@ -179,14 +177,13 @@ void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims) void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) { - int16_t accADCRaw[XYZ_AXIS_COUNT]; - int axis; + int16_t accADCRaw[XYZ_AXIS_COUNT]; if (!acc.read(accADCRaw)) { return; } - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { if (debugMode == DEBUG_ACCELEROMETER) debug[axis] = accADCRaw[axis]; accSmooth[axis] = accADCRaw[axis]; } @@ -194,13 +191,17 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) if (accLpfCutHz) { if (!accFilterInitialised) { if (accTargetLooptime) { /* Initialisation needs to happen once sample rate is known */ - for (axis = 0; axis < 3; axis++) BiQuadNewLpf(accLpfCutHz, &accFilterState[axis], accTargetLooptime); + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + biquadFilterInit(&accFilter[axis], accLpfCutHz, accTargetLooptime); + } accFilterInitialised = true; } } if (accFilterInitialised) { - for (axis = 0; axis < XYZ_AXIS_COUNT; axis++) accSmooth[axis] = lrintf(applyBiQuadFilter((float) accSmooth[axis], &accFilterState[axis])); + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + accSmooth[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float)accSmooth[axis])); + } } } diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 5bcc265f16..23159d87cd 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -63,20 +63,19 @@ uint16_t batteryAdcToVoltage(uint16_t src) static void updateBatteryVoltage(void) { - uint16_t vbatSample; - static biquad_t vbatFilterState; - static bool vbatFilterStateIsSet; + static biquadFilter_t vbatFilter; + static bool vbatFilterIsInitialised; // store the battery voltage with some other recent battery voltage readings - vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY); + uint16_t vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY); if (debugMode == DEBUG_BATTERY) debug[0] = vbatSample; - if (!vbatFilterStateIsSet) { - BiQuadNewLpf(VBATT_LPF_FREQ, &vbatFilterState, 50000); //50HZ Update - vbatFilterStateIsSet = true; + if (!vbatFilterIsInitialised) { + biquadFilterInit(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update + vbatFilterIsInitialised = true; } - vbatSample = applyBiQuadFilter(vbatSample, &vbatFilterState); + vbatSample = biquadFilterApply(&vbatFilter, vbatSample); vbat = batteryAdcToVoltage(vbatSample); if (debugMode == DEBUG_BATTERY) debug[1] = vbat; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index c79d29013f..4f425dc1d2 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -43,7 +43,7 @@ float gyroADCf[XYZ_AXIS_COUNT]; static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 }; static const gyroConfig_t *gyroConfig; -static biquad_t gyroFilterState[XYZ_AXIS_COUNT]; +static biquadFilter_t gyroFilter[XYZ_AXIS_COUNT]; static uint8_t gyroSoftLpfHz; static uint16_t calibratingG = 0; @@ -57,7 +57,7 @@ void gyroInit(void) { if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known for (int axis = 0; axis < 3; axis++) { - BiQuadNewLpf(gyroSoftLpfHz, &gyroFilterState[axis], gyro.targetLooptime); + biquadFilterInit(&gyroFilter[axis], gyroSoftLpfHz, gyro.targetLooptime); } } } @@ -157,7 +157,7 @@ void gyroUpdate(void) if (gyroSoftLpfHz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - gyroADCf[axis] = applyBiQuadFilter((float)gyroADC[axis], &gyroFilterState[axis]); + gyroADCf[axis] = biquadFilterApply(&gyroFilter[axis], (float)gyroADC[axis]); gyroADC[axis] = lrintf(gyroADCf[axis]); } } else { From 325f4297cc33b051754f4508729ecc3e34087ac9 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Sun, 3 Jul 2016 03:49:39 -0700 Subject: [PATCH 055/108] Fix typo - replace rrc by rcc --- src/main/drivers/dma.c | 2 +- src/main/drivers/dma.h | 8 ++++---- src/main/drivers/dma_stm32f4xx.c | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index cbcaa5eafb..4b6cace0e5 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -75,7 +75,7 @@ void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr { NVIC_InitTypeDef NVIC_InitStructure; - RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rrc, ENABLE); + RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE); dmaDescriptors[identifier].irqHandlerCallback = callback; dmaDescriptors[identifier].userParam = userParam; diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index e0bbdfd12b..4f0dabdfff 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -44,11 +44,11 @@ typedef struct dmaChannelDescriptor_s { dmaCallbackHandlerFuncPtr irqHandlerCallback; uint8_t flagsShift; IRQn_Type irqN; - uint32_t rrc; + uint32_t rcc; uint32_t userParam; } dmaChannelDescriptor_t; -#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rrc = r, .userParam = 0} +#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0} #define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\ if (dmaDescriptors[i].irqHandlerCallback)\ dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ @@ -87,11 +87,11 @@ typedef struct dmaChannelDescriptor_s { dmaCallbackHandlerFuncPtr irqHandlerCallback; uint8_t flagsShift; IRQn_Type irqN; - uint32_t rrc; + uint32_t rcc; uint32_t userParam; } dmaChannelDescriptor_t; -#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rrc = r, .userParam = 0} +#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0} #define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\ if (dmaDescriptors[i].irqHandlerCallback)\ dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\ diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index 4661864867..bf2d2ec582 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -76,7 +76,7 @@ void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr { NVIC_InitTypeDef NVIC_InitStructure; - RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rrc, ENABLE); + RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE); dmaDescriptors[identifier].irqHandlerCallback = callback; dmaDescriptors[identifier].userParam = userParam; From 39ec4a128ab3fe67d094b42e0693fb993f22c84b Mon Sep 17 00:00:00 2001 From: kc10kevin Date: Mon, 4 Jul 2016 02:16:44 -0500 Subject: [PATCH 056/108] FuryF4 Target Changes --- src/main/target/FURYF4/target.h | 32 ++++++++++++++++++++++---------- 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 397206c9bc..2559e2d27d 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -17,13 +17,10 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "FYF4" //Call it a revo for now so it connects to RFC for testing. +#define TARGET_BOARD_IDENTIFIER "FYF4" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH -#define CONFIG_MSP_PORT 2 -#define CONFIG_RX_SERIAL_PORT 1 -#define USBD_PRODUCT_STRING "FURYF4" +#define USBD_PRODUCT_STRING "FuryF4" #define LED0 PB5 #define LED1 PB4 @@ -67,8 +64,8 @@ #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PD2 -#define SDCARD_SPI_INSTANCE SPI3 -#define SDCARD_SPI_CS_PIN PB3 +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_PIN PB12 /* #define SDCARD_DETECT_PIN PD2 @@ -86,11 +83,18 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz -#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5 -#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5 + +//#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5 +//#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5 +//#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 +//#define SDCARD_DMA_CHANNEL DMA_Channel_0 + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CHANNEL DMA_Channel_0 + #define USE_FLASHFS #define USE_FLASH_M25P16 #define M25P16_CS_PIN PB3 @@ -149,10 +153,18 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define SPEKTRUM_BIND +// USART3 Rx, PB11 +#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 0xffff +#define TARGET_IO_PORTD (BIT(2)) #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9)) From c7c459d122fd4f55cae47680ddba1dee3dbce2ac Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 5 Jul 2016 01:13:31 +0200 Subject: [PATCH 057/108] Add GYRO INT to KISS target --- src/main/target/KISSFC/target.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 03c3cf31f6..04e319cf38 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -28,9 +28,10 @@ #define USABLE_TIMER_CHANNEL_COUNT 12 -#define EXTI2_TS_CALLBACK_HANDLER_COUNT 1 // MPU data ready +#define USE_EXTI +#define MPU_INT_EXTI PB2 #define USE_MPU_DATA_READY_SIGNAL - +#define ENSURE_MPU_DATA_READY_IS_LOW #define GYRO #define USE_GYRO_MPU6050 From 67a48ca4c9790d05a5f71700226ff1922a306df2 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Mon, 4 Jul 2016 07:46:49 +0200 Subject: [PATCH 058/108] Move custom configuration for AlienFlight and Colibri Race to target directory --- src/main/config/config.c | 36 +-------- src/main/target/ALIENFLIGHTF3/config.c | 100 +++++++++++++++++++++++++ src/main/target/ALIENFLIGHTF3/target.h | 2 +- src/main/target/ALIENFLIGHTF4/config.c | 100 +++++++++++++++++++++++++ src/main/target/ALIENFLIGHTF4/target.h | 4 +- src/main/target/COLIBRI_RACE/config.c | 84 +++++++++++++++++++++ src/main/target/COLIBRI_RACE/target.h | 1 + src/main/target/NAZE/config.c | 99 ++++++++++++++++++++++++ src/main/target/NAZE/target.h | 2 +- 9 files changed, 389 insertions(+), 39 deletions(-) create mode 100644 src/main/target/ALIENFLIGHTF3/config.c create mode 100644 src/main/target/ALIENFLIGHTF4/config.c create mode 100644 src/main/target/COLIBRI_RACE/config.c create mode 100644 src/main/target/NAZE/config.c diff --git a/src/main/config/config.c b/src/main/config/config.c index bc8d830a59..003b7c32a7 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -89,6 +89,7 @@ #endif void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); +void targetConfiguration(void); #if !defined(FLASH_SIZE) #error "Flash size not defined for target. (specify in KB)" @@ -652,41 +653,8 @@ static void resetConf(void) } #endif - // alternative defaults settings for COLIBRI RACE targets -#if defined(COLIBRI_RACE) - masterConfig.escAndServoConfig.minthrottle = 1025; - masterConfig.escAndServoConfig.maxthrottle = 1980; - masterConfig.batteryConfig.vbatmaxcellvoltage = 45; - masterConfig.batteryConfig.vbatmincellvoltage = 30; -#endif - #if defined(TARGET_CONFIG) - targetConfiguration(&masterConfig); -#endif - -#if defined(ALIENFLIGHT) - featureClear(FEATURE_ONESHOT125); -#ifdef ALIENFLIGHTF3 - masterConfig.mag_hardware = MAG_NONE; // disabled by default -#endif - masterConfig.rxConfig.spektrum_sat_bind = 5; - masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; - masterConfig.motor_pwm_rate = 32000; - masterConfig.failsafeConfig.failsafe_delay = 2; - masterConfig.failsafeConfig.failsafe_off_delay = 0; - currentControlRateProfile->rates[FD_PITCH] = 40; - currentControlRateProfile->rates[FD_ROLL] = 40; - currentControlRateProfile->rates[FD_YAW] = 40; - parseRcChannels("TAER1234", &masterConfig.rxConfig); - - masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R - masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R - masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L - masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L - masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R - masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L - masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R - masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif + targetConfiguration(); #endif // copy first profile into remaining profile diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c new file mode 100644 index 0000000000..9defa6223a --- /dev/null +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -0,0 +1,100 @@ +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 4cd3d955cb..1df1d3c4fd 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -18,7 +18,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. -#define ALIENFLIGHT +#define TARGET_CONFIG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c new file mode 100644 index 0000000000..9defa6223a --- /dev/null +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -0,0 +1,100 @@ +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 98387ee23c..54983b3d2e 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -17,6 +17,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "AFF4" +#define TARGET_CONFIG #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) @@ -153,9 +154,6 @@ //#define WS2811_DMA_CHANNEL DMA1_Channel3 //#define WS2811_IRQ DMA1_Channel3_IRQn -// alternative defaults for AlienFlight F4 target -#define ALIENFLIGHT - #define SPEKTRUM_BIND // USART2, PA3 #define BIND_PIN PA3 diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c new file mode 100644 index 0000000000..ff958beb56 --- /dev/null +++ b/src/main/target/COLIBRI_RACE/config.c @@ -0,0 +1,84 @@ +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for COLIBRI RACE targets +void targetConfiguration(void) { + masterConfig.escAndServoConfig.minthrottle = 1025; + masterConfig.escAndServoConfig.maxthrottle = 1980; + masterConfig.batteryConfig.vbatmaxcellvoltage = 45; + masterConfig.batteryConfig.vbatmincellvoltage = 30; +} diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 2139ebb37d..0492926e55 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -20,6 +20,7 @@ #define TARGET_BOARD_IDENTIFIER "CLBR" #define BST_DEVICE_NAME "COLIBRI RACE" #define BST_DEVICE_NAME_LENGTH 12 +#define TARGET_CONFIG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c new file mode 100644 index 0000000000..e0592bbf9d --- /dev/null +++ b/src/main/target/NAZE/config.c @@ -0,0 +1,99 @@ +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index cb2f575392..cc8b93c09f 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -172,7 +172,7 @@ // alternative defaults for AlienFlight F1 target #undef TARGET_BOARD_IDENTIFIER #define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1. -#define ALIENFLIGHT +#define TARGET_CONFIG #undef BOARD_HAS_VOLTAGE_DIVIDER #undef USE_SERIAL_4WAY_BLHELI_INTERFACE From 0b48943a3cb376aebfa22098a8452ecd782e0a2b Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 5 Jul 2016 22:03:18 +1000 Subject: [PATCH 059/108] Fix ADC STM32F3 define --- src/main/drivers/adc_stm32f30x.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 3fc7427b5a..0116a6734a 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -117,13 +117,13 @@ void adcInit(drv_adc_config_t *init) } #endif -#ifdef CURRENT_METER_ADC_GPIO +#ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); } #endif -#ifdef EXTERNAL1_ADC_GPIO +#ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); } From b274289f0c8233be35dbf857026cf3a4409937b7 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 5 Jul 2016 16:48:31 +0200 Subject: [PATCH 060/108] Move PPM pin for KISS FC to PITCH --- src/main/target/KISSFC/target.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index 07450ad505..cf260d6d96 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -22,7 +22,7 @@ #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { - PWM7 | (MAP_TO_PPM_INPUT << 8), + PWM9 | (MAP_TO_PPM_INPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -44,7 +44,7 @@ const uint16_t multiPWM[] = { PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM8 | (MAP_TO_PWM_INPUT << 8), PWM9 | (MAP_TO_PWM_INPUT << 8), PWM10 | (MAP_TO_PWM_INPUT << 8), @@ -71,7 +71,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1}, - { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, From 0c270b8eeaf2441fb3d9d3b2d2962628ac6faab4 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 5 Jul 2016 22:40:08 +0200 Subject: [PATCH 061/108] Remove double pin assignment for KISS FC --- src/main/target/KISSFC/target.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index cf260d6d96..e270422ad6 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -30,7 +30,6 @@ const uint16_t multiPPM[] = { PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), From 19799ed66f18219dcd630c50a73a8eacca818111 Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Tue, 5 Jul 2016 22:47:10 +0200 Subject: [PATCH 062/108] Some merge artifacts from @MJ666 --- src/main/target/ALIENFLIGHTF3/config.c | 200 ++++++++++++------------- src/main/target/ALIENFLIGHTF4/config.c | 200 ++++++++++++------------- src/main/target/COLIBRI_RACE/config.c | 168 ++++++++++----------- src/main/target/NAZE/config.c | 198 ++++++++++++------------ 4 files changed, 383 insertions(+), 383 deletions(-) diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index 9defa6223a..8c693a98cf 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -1,100 +1,100 @@ -/* - * 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 . - */ - -#include - -#include - -#include "build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/escservo.h" -#include "io/rc_controls.h" -#include "io/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "config/runtime_config.h" -#include "config/config.h" - -#include "config/config_profile.h" -#include "config/config_master.h" - -// alternative defaults settings for AlienFlight targets -void targetConfiguration(void) { - featureClear(FEATURE_ONESHOT125); - masterConfig.mag_hardware = MAG_NONE; // disabled by default - masterConfig.rxConfig.spektrum_sat_bind = 5; - masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; - masterConfig.motor_pwm_rate = 32000; - masterConfig.failsafeConfig.failsafe_delay = 2; - masterConfig.failsafeConfig.failsafe_off_delay = 0; - currentControlRateProfile->rates[FD_PITCH] = 40; - currentControlRateProfile->rates[FD_ROLL] = 40; - currentControlRateProfile->rates[FD_YAW] = 40; - parseRcChannels("TAER1234", &masterConfig.rxConfig); - - masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R - masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R - masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L - masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L - masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R - masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L - masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R - masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif -} +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index 9defa6223a..8c693a98cf 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -1,100 +1,100 @@ -/* - * 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 . - */ - -#include - -#include - -#include "build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/escservo.h" -#include "io/rc_controls.h" -#include "io/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "config/runtime_config.h" -#include "config/config.h" - -#include "config/config_profile.h" -#include "config/config_master.h" - -// alternative defaults settings for AlienFlight targets -void targetConfiguration(void) { - featureClear(FEATURE_ONESHOT125); - masterConfig.mag_hardware = MAG_NONE; // disabled by default - masterConfig.rxConfig.spektrum_sat_bind = 5; - masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; - masterConfig.motor_pwm_rate = 32000; - masterConfig.failsafeConfig.failsafe_delay = 2; - masterConfig.failsafeConfig.failsafe_off_delay = 0; - currentControlRateProfile->rates[FD_PITCH] = 40; - currentControlRateProfile->rates[FD_ROLL] = 40; - currentControlRateProfile->rates[FD_YAW] = 40; - parseRcChannels("TAER1234", &masterConfig.rxConfig); - - masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R - masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R - masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L - masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L - masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R - masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L - masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R - masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif -} +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c index ff958beb56..bbd5a49c9c 100644 --- a/src/main/target/COLIBRI_RACE/config.c +++ b/src/main/target/COLIBRI_RACE/config.c @@ -1,84 +1,84 @@ -/* - * 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 . - */ - -#include - -#include - -#include "build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/escservo.h" -#include "io/rc_controls.h" -#include "io/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "config/runtime_config.h" -#include "config/config.h" - -#include "config/config_profile.h" -#include "config/config_master.h" - -// alternative defaults settings for COLIBRI RACE targets -void targetConfiguration(void) { - masterConfig.escAndServoConfig.minthrottle = 1025; - masterConfig.escAndServoConfig.maxthrottle = 1980; - masterConfig.batteryConfig.vbatmaxcellvoltage = 45; - masterConfig.batteryConfig.vbatmincellvoltage = 30; -} +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for COLIBRI RACE targets +void targetConfiguration(void) { + masterConfig.escAndServoConfig.minthrottle = 1025; + masterConfig.escAndServoConfig.maxthrottle = 1980; + masterConfig.batteryConfig.vbatmaxcellvoltage = 45; + masterConfig.batteryConfig.vbatmincellvoltage = 30; +} diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index e0592bbf9d..f9fde08608 100644 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -1,99 +1,99 @@ -/* - * 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 . - */ - -#include - -#include - -#include "build_config.h" - -#include "blackbox/blackbox_io.h" - -#include "common/color.h" -#include "common/axis.h" -#include "common/filter.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/compass.h" -#include "drivers/system.h" -#include "drivers/timer.h" -#include "drivers/pwm_rx.h" -#include "drivers/serial.h" -#include "drivers/pwm_output.h" -#include "drivers/max7456.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" - -#include "sensors/sensors.h" -#include "sensors/gyro.h" -#include "sensors/compass.h" -#include "sensors/acceleration.h" -#include "sensors/barometer.h" -#include "sensors/boardalignment.h" -#include "sensors/battery.h" - -#include "io/beeper.h" -#include "io/serial.h" -#include "io/gimbal.h" -#include "io/escservo.h" -#include "io/rc_controls.h" -#include "io/rc_curves.h" -#include "io/ledstrip.h" -#include "io/gps.h" -#include "io/osd.h" -#include "io/vtx.h" - -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "flight/mixer.h" -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/failsafe.h" -#include "flight/altitudehold.h" -#include "flight/navigation.h" - -#include "config/runtime_config.h" -#include "config/config.h" - -#include "config/config_profile.h" -#include "config/config_master.h" - -// alternative defaults settings for AlienFlight targets -void targetConfiguration(void) { - featureClear(FEATURE_ONESHOT125); - masterConfig.rxConfig.spektrum_sat_bind = 5; - masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; - masterConfig.motor_pwm_rate = 32000; - masterConfig.failsafeConfig.failsafe_delay = 2; - masterConfig.failsafeConfig.failsafe_off_delay = 0; - currentControlRateProfile->rates[FD_PITCH] = 40; - currentControlRateProfile->rates[FD_ROLL] = 40; - currentControlRateProfile->rates[FD_YAW] = 40; - parseRcChannels("TAER1234", &masterConfig.rxConfig); - - masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R - masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R - masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L - masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L - masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R - masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L - masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R - masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif -} +/* + * 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 . + */ + +#include + +#include + +#include "build_config.h" + +#include "blackbox/blackbox_io.h" + +#include "common/color.h" +#include "common/axis.h" +#include "common/filter.h" + +#include "drivers/sensor.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/system.h" +#include "drivers/timer.h" +#include "drivers/pwm_rx.h" +#include "drivers/serial.h" +#include "drivers/pwm_output.h" +#include "drivers/max7456.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" + +#include "sensors/sensors.h" +#include "sensors/gyro.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/barometer.h" +#include "sensors/boardalignment.h" +#include "sensors/battery.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/gimbal.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/rc_curves.h" +#include "io/ledstrip.h" +#include "io/gps.h" +#include "io/osd.h" +#include "io/vtx.h" + +#include "rx/rx.h" + +#include "telemetry/telemetry.h" + +#include "flight/mixer.h" +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/failsafe.h" +#include "flight/altitudehold.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" + +#include "config/config_profile.h" +#include "config/config_master.h" + +// alternative defaults settings for AlienFlight targets +void targetConfiguration(void) { + featureClear(FEATURE_ONESHOT125); + masterConfig.rxConfig.spektrum_sat_bind = 5; + masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1; + masterConfig.motor_pwm_rate = 32000; + masterConfig.failsafeConfig.failsafe_delay = 2; + masterConfig.failsafeConfig.failsafe_off_delay = 0; + currentControlRateProfile->rates[FD_PITCH] = 40; + currentControlRateProfile->rates[FD_ROLL] = 40; + currentControlRateProfile->rates[FD_YAW] = 40; + parseRcChannels("TAER1234", &masterConfig.rxConfig); + + masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R + masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R + masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L + masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L + masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R + masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L + masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R + masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif +} From 688a4ad376a31d6f24256f589da0359123a70007 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 6 Jul 2016 07:46:38 +1000 Subject: [PATCH 063/108] Setup SPI pins for F1 fix --- src/main/drivers/bus_spi.c | 6 +++--- src/main/drivers/bus_spi.h | 6 ++++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index c78c2024a9..90224cefcc 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -132,9 +132,9 @@ void spiInitDevice(SPIDevice device) IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); #endif #if defined(STM32F10X) - IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG); - IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG); - IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG); + IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); + IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); + IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); if (spi->nss) IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 019080d963..64046904fe 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -27,8 +27,10 @@ #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP) #define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #elif defined(STM32F1) -#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz) -#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) +#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) +#define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) +#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) #else #error "Unknown processor" #endif From cc5cde11128a92f83fcc7218bb938688a0c1dc6a Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 6 Jul 2016 00:29:57 +0200 Subject: [PATCH 064/108] Add CPU load to MSP --- src/main/io/serial_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index b616605ac3..4eb59402c8 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -747,7 +747,7 @@ static bool processOutCommand(uint8_t cmdMSP) serialize16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); serialize32(packFlightModeFlags()); serialize8(masterConfig.current_profile_index); - //serialize16(averageSystemLoadPercent); + serialize16(constrain(averageSystemLoadPercent, 0, 100)); break; case MSP_STATUS: From 09b4768d188f025cb41e13a388f7a7fdd59c7782 Mon Sep 17 00:00:00 2001 From: flyinglemonfpv Date: Wed, 6 Jul 2016 09:08:40 +0200 Subject: [PATCH 065/108] Add AiR32 target --- src/main/target/AIR32/target.c | 55 ++++++++++ src/main/target/AIR32/target.h | 178 ++++++++++++++++++++++++++++++++ src/main/target/AIR32/target.mk | 14 +++ 3 files changed, 247 insertions(+) create mode 100644 src/main/target/AIR32/target.c create mode 100644 src/main/target/AIR32/target.h create mode 100644 src/main/target/AIR32/target.mk diff --git a/src/main/target/AIR32/target.c b/src/main/target/AIR32/target.c new file mode 100644 index 0000000000..47789fd4f8 --- /dev/null +++ b/src/main/target/AIR32/target.c @@ -0,0 +1,55 @@ + +#include +#include + +#include +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + // TODO + 0xFFFF +}; + +const uint16_t airPWM[] = { + // TODO + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 +}; + diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h new file mode 100644 index 0000000000..754e9324ee --- /dev/null +++ b/src/main/target/AIR32/target.h @@ -0,0 +1,178 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "AR32" // AiR32 +#define USE_CLI + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define LED0 PB5 // Blue LED - PB5 + + +#define BEEPER PA0 + + +#define USABLE_TIMER_CHANNEL_COUNT 9 + +// MPU6050 interrupts +#define USE_EXTI +#define MPU_INT_EXTI PA15 +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready +#define USE_MPU_DATA_READY_SIGNAL +//#define ENSURE_MPU_DATA_READY_IS_LOW + +#define GYRO +#define ACC + +#define USE_GYRO_MPU6050 +#define GYRO_MPU6050_ALIGN CW180_DEG + +#define USE_ACC_MPU6050 + +#define ACC_MPU6050_ALIGN CW180_DEG + +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG + +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 + +//#define BARO +//#define USE_BARO_MS5611 + +//#define MAG +//#define USE_MAG_HMC5883 + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define SERIAL_PORT_COUNT 4 + +#define UART1_TX_PIN GPIO_Pin_6 // PB6 +#define UART1_RX_PIN GPIO_Pin_7 // PB7 +#define UART1_GPIO GPIOB +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource6 +#define UART1_RX_PINSOURCE GPIO_PinSource7 + +#define UART2_TX_PIN GPIO_Pin_3 // PB3 +#define UART2_RX_PIN GPIO_Pin_4 // PB4 +#define UART2_GPIO GPIOB +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource3 +#define UART2_RX_PINSOURCE GPIO_PinSource4 + +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) + +#define I2C2_SCL_GPIO GPIOA +#define I2C2_SCL_GPIO_AF GPIO_AF_4 +#define I2C2_SCL_PIN PA9 +#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 +#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA +#define I2C2_SDA_GPIO GPIOA +#define I2C2_SDA_GPIO_AF GPIO_AF_4 +#define I2C2_SDA_PIN PA10 +#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 +#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA + +#define USE_SPI +#define USE_SPI_DEVICE_2 + +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 + +//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG) +#define SENSORS_SET (SENSOR_ACC) + +#undef GPS +#define DISPLAY +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA5 +//#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 + +#define LED_STRIP +#if 1 +#define LED_STRIP_TIMER TIM16 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL3 +#define WS2811_GPIO GPIOB +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM16 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER +#endif + +#if 0 +// Alternate LED strip pin +// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1 +#define LED_STRIP_TIMER TIM17 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL7 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource7 +#define WS2811_TIMER TIM17 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17 +#define WS2811_DMA_CHANNEL DMA1_Channel7 +#define WS2811_IRQ DMA1_Channel7_IRQn +#endif + + +#define SPEKTRUM_BIND +// USART2, PB4 +#define BIND_PIN PB4 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +// #define TARGET_IO_PORTF (BIT(0)|BIT(1)) +// !!TODO - check the following line is correct +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) + diff --git a/src/main/target/AIR32/target.mk b/src/main/target/AIR32/target.mk new file mode 100644 index 0000000000..8613619434 --- /dev/null +++ b/src/main/target/AIR32/target.mk @@ -0,0 +1,14 @@ +F3_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/inverter.c \ + drivers/serial_softserial.c + From d50e1e2fff78720282951608025411080dd18081 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 6 Jul 2016 10:05:53 +0100 Subject: [PATCH 066/108] Changed CC3D default RX to PPM --- src/main/target/CC3D/target.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 8d6e6afbc3..5e6c1b8ad0 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -124,6 +124,8 @@ #undef SONAR #endif +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM + // IO - from schematics #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff From 6b975db3c0650c56accf7e6a0b83880d8943ea82 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 6 Jul 2016 10:08:15 +0100 Subject: [PATCH 067/108] Fixed up REVO default features --- src/main/target/REVO/target.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 3a67944b91..2532d43878 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -111,8 +111,8 @@ #define SENSORS_SET (SENSOR_ACC) -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125 | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define USE_SERIAL_4WAY_BLHELI_INTERFACE From 73d5fd179498fbd4f19f13048cfeea7707e1976f Mon Sep 17 00:00:00 2001 From: johnlemon Date: Wed, 6 Jul 2016 13:44:38 +0200 Subject: [PATCH 068/108] clean up --- src/main/target/AIR32/target.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/AIR32/target.mk b/src/main/target/AIR32/target.mk index 8613619434..7151bafad9 100644 --- a/src/main/target/AIR32/target.mk +++ b/src/main/target/AIR32/target.mk @@ -9,6 +9,6 @@ TARGET_SRC = \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ - drivers/inverter.c \ + drivers/inverter.c \ drivers/serial_softserial.c From 04658cab4f6ccfc5cf81ba2ff0c964332d882c50 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Wed, 6 Jul 2016 07:53:06 +0200 Subject: [PATCH 069/108] Adding back the third profile for targets with more than 128kB flash --- src/main/config/config.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/config/config.h b/src/main/config/config.h index c26bbe6455..5a46a78c33 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -17,7 +17,11 @@ #pragma once +#if FLASH_SIZE <= 128 #define MAX_PROFILE_COUNT 2 +#else +#define MAX_PROFILE_COUNT 3 +#endif #define MAX_RATEPROFILES 3 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 From d366af00c6843cf66e3130c49ef4fff14d948159 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Fri, 8 Jul 2016 10:29:16 +0100 Subject: [PATCH 070/108] Fixed GPS speed --- src/main/telemetry/hott.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/telemetry/hott.c b/src/main/telemetry/hott.c index 6fb0bc1a92..7ccf8ea197 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -193,15 +193,15 @@ void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage) addGPSCoordinates(hottGPSMessage, GPS_coord[LAT], GPS_coord[LON]); - // GPS Speed in km/h - uint16_t speed = (GPS_speed * 36) / 100; // 0->1m/s * 0->36 = km/h + // GPS Speed is returned in cm/s (from io/gps.c) and must be sent in km/h (Hott requirement) + const uint16_t speed = (GPS_speed * 36) / 1000; hottGPSMessage->gps_speed_L = speed & 0x00FF; hottGPSMessage->gps_speed_H = speed >> 8; hottGPSMessage->home_distance_L = GPS_distanceToHome & 0x00FF; hottGPSMessage->home_distance_H = GPS_distanceToHome >> 8; - uint16_t hottGpsAltitude = (GPS_altitude) + HOTT_GPS_ALTITUDE_OFFSET; // GPS_altitude in m ; offset = 500 -> O m + const uint16_t hottGpsAltitude = (GPS_altitude) + HOTT_GPS_ALTITUDE_OFFSET; // GPS_altitude in m ; offset = 500 -> O m hottGPSMessage->altitude_L = hottGpsAltitude & 0x00FF; hottGPSMessage->altitude_H = hottGpsAltitude >> 8; From 2d96e29e073d2734d0456142ab4733a1faacdae4 Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Fri, 8 Jul 2016 18:12:47 +0200 Subject: [PATCH 071/108] SPI CS must be driven high also on F1. Some do not have external pullups. --- src/main/drivers/bus_spi.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 64046904fe..dbba94881c 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -30,7 +30,7 @@ #define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz) -#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz) #else #error "Unknown processor" #endif From 5d45a2fc4227105e73e17b9dd1e846ee0860fe59 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Fri, 8 Jul 2016 23:23:20 +0100 Subject: [PATCH 072/108] Defined SPIn_NSS_PINs in target.h files --- src/main/target/COLIBRI_RACE/target.h | 12 +++++++----- src/main/target/DOGE/target.h | 25 +++++++++++++++---------- src/main/target/LUX_RACE/target.h | 9 ++++----- 3 files changed, 26 insertions(+), 20 deletions(-) diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 0492926e55..8fb4cee7a2 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -32,11 +32,6 @@ #define BEEPER_INVERTED #define USE_EXTI -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 - -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 #define USE_SPI #define USE_SPI_DEVICE_1 @@ -44,6 +39,13 @@ #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 +#define SPI1_NSS_PIN PA4 + +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 + +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_INSTANCE SPI1 #define USABLE_TIMER_CHANNEL_COUNT 11 diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 7ca509ea28..c790c52421 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -33,14 +33,6 @@ #define BEEPER PB2 #define BEEPER_INVERTED -// tqfp48 pin 3 -#define MPU6500_CS_PIN PC14 -#define MPU6500_SPI_INSTANCE SPI1 - -// tqfp48 pin 25 -#define BMP280_CS_PIN PB12 -#define BMP280_SPI_INSTANCE SPI2 - #define USE_SPI #define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_2 @@ -51,18 +43,31 @@ #define SPI1_MISO_PIN PB4 // tqfp48 pin 41 #define SPI1_MOSI_PIN PB5 +// tqfp48 pin 3 +#define SPI1_NSS_PIN PC14 + // tqfp48 pin 26 #define SPI2_SCK_PIN PB13 // tqfp48 pin 27 #define SPI2_MISO_PIN PB14 // tqfp48 pin 28 #define SPI2_MOSI_PIN PB15 +// tqfp48 pin 25 +#define SPI2_NSS_PIN PB12 + +// tqfp48 pin 3 +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 + +// tqfp48 pin 25 +#define BMP280_CS_PIN SPI2_NSS_PIN +#define BMP280_SPI_INSTANCE SPI2 #define USE_FLASHFS #define USE_FLASH_M25P16 #define M25P16_SPI_SHARED -#define M25P16_CS_PIN PC15 -#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_CS_PIN PC15 +#define M25P16_SPI_INSTANCE SPI2 // timer definitions in drivers/timer.c // channel mapping in drivers/pwm_mapping.c diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index cef9b31b0a..600bd2ee66 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -29,17 +29,16 @@ #define BEEPER PB13 #define BEEPER_INVERTED -#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA -#define MPU6500_CS_GPIO GPIOA -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 - #define USE_SPI #define USE_SPI_DEVICE_1 #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 +#define SPI1_NSS_PIN PA4 + +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 #define USABLE_TIMER_CHANNEL_COUNT 11 From 5f034705574b690aa0a5c79c6aa981b45cf7c9a3 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 4 Jul 2016 22:06:20 +1000 Subject: [PATCH 073/108] STM32F1/3: convert serial UART to IO code --- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/serial_uart_stm32f10x.c | 80 +++---- src/main/drivers/serial_uart_stm32f30x.c | 258 +++++++---------------- src/main/target/ALIENFLIGHTF3/target.h | 25 +-- src/main/target/CC3D/target.h | 11 +- src/main/target/CHEBUZZF3/target.h | 2 +- src/main/target/COLIBRI_RACE/target.h | 24 +-- src/main/target/DOGE/target.h | 30 +-- src/main/target/FURYF3/target.h | 28 +-- src/main/target/IRCFUSIONF3/target.h | 28 +-- src/main/target/KISSFC/target.h | 27 +-- src/main/target/LUX_RACE/target.h | 24 +-- src/main/target/MOTOLAB/target.h | 24 +-- src/main/target/NAZE/target.h | 7 +- src/main/target/OMNIBUS/target.h | 28 +-- src/main/target/PIKOBLX/target.h | 24 +-- src/main/target/RMDO/target.h | 28 +-- src/main/target/SINGULARITY/target.h | 25 +-- src/main/target/SIRINFPV/target.h | 28 +-- src/main/target/SPARKY/target.h | 24 +-- src/main/target/SPRACINGF3/target.h | 28 +-- src/main/target/SPRACINGF3EVO/target.h | 28 +-- src/main/target/SPRACINGF3MINI/target.h | 28 +-- src/main/target/X_RACERSPI/target.h | 28 +-- src/main/target/ZCOREF3/target.h | 26 +-- src/main/target/common.h | 6 + 26 files changed, 236 insertions(+), 635 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 5e797ea2f0..fe2c5f24b4 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -144,7 +144,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #if defined(STM32F303xC) && defined(USE_USART3) // skip UART3 ports (PB10/PB11) - if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_RX_PIN))) + if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN))) continue; #endif diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 08c16fa2f3..473689a8bb 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -29,8 +29,9 @@ #include #include "system.h" -#include "gpio.h" +#include "io.h" #include "nvic.h" +#include "rcc.h" #include "serial.h" #include "serial_uart.h" @@ -48,13 +49,6 @@ static uartPort_t uartPort2; static uartPort_t uartPort3; #endif -// Using RX DMA disables the use of receive callbacks -#define USE_USART1_RX_DMA - -#if defined(CC3D) // FIXME move board specific code to target.h files. -#undef USE_USART1_RX_DMA -#endif - void usartIrqCallback(uartPort_t *s) { uint16_t SR = s->USARTx->SR; @@ -89,7 +83,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; - gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort1; @@ -112,27 +106,23 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAChannel = DMA1_Channel4; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB2(USART1), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); // USART1_TX PA9 // USART1_RX PA10 - gpio.speed = Speed_2MHz; - - gpio.pin = Pin_9; if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - gpio.mode = Mode_AF_PP; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP); } if (mode & MODE_RX) { - gpio.pin = Pin_10; - gpio.mode = Mode_IPU; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU); } } @@ -155,7 +145,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio return s; } - // USART1 Tx DMA Handler void DMA1_Channel4_IRQHandler(void) { @@ -185,7 +174,7 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; - gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort2; @@ -203,27 +192,23 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB1(USART2), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); // USART2_TX PA2 // USART2_RX PA3 - gpio.speed = Speed_2MHz; - - gpio.pin = Pin_2; if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - gpio.mode = Mode_AF_PP; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP); } if (mode & MODE_RX) { - gpio.pin = Pin_3; - gpio.mode = Mode_IPU; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } @@ -254,7 +239,7 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE]; - gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort3; @@ -272,29 +257,20 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; -#ifdef USART3_APB1_PERIPHERALS - RCC_APB1PeriphClockCmd(USART3_APB1_PERIPHERALS, ENABLE); -#endif -#ifdef USART3_APB2_PERIPHERALS - RCC_APB2PeriphClockCmd(USART3_APB2_PERIPHERALS, ENABLE); -#endif + RCC_ClockCmd(RCC_APB1(USART3), ENABLE); - gpio.speed = Speed_2MHz; - - gpio.pin = USART3_TX_PIN; if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(USART3_GPIO, &gpio); + IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - gpio.mode = Mode_AF_PP; - gpioInit(USART3_GPIO, &gpio); + IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_TX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_PP); } if (mode & MODE_RX) { - gpio.pin = USART3_RX_PIN; - gpio.mode = Mode_IPU; - gpioInit(USART3_GPIO, &gpio); + IOInit(IOGetByTag(IO_TAG(USART3_RX_PIN)), OWNER_SERIAL_RX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(USART3_RX_PIN)), IOCFG_IPU); } } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index f457288ac9..f8c0c57893 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -30,63 +30,57 @@ #include #include "system.h" -#include "gpio.h" +#include "io.h" #include "nvic.h" +#include "rcc.h" #include "serial.h" #include "serial_uart.h" #include "serial_uart_impl.h" -// Using RX DMA disables the use of receive callbacks -//#define USE_USART1_RX_DMA -//#define USE_USART2_RX_DMA -//#define USE_USART2_TX_DMA -//#define USE_USART3_RX_DMA -//#define USE_USART3_TX_DMA - -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#ifdef USE_USART1 +#ifndef UART1_TX_PIN +#define UART1_TX_PIN PA9 // PA9 +#endif +#ifndef UART1_RX_PIN +#define UART1_RX_PIN PA10 // PA10 +#endif #endif -#ifndef UART2_GPIO -#define UART2_TX_PIN GPIO_Pin_5 // PD5 -#define UART2_RX_PIN GPIO_Pin_6 // PD6 -#define UART2_GPIO GPIOD -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource5 -#define UART2_RX_PINSOURCE GPIO_PinSource6 +#ifdef USE_USART2 +#ifndef UART2_TX_PIN +#define UART2_TX_PIN PD5 // PD5 +#endif +#ifndef UART2_RX_PIN +#define UART2_RX_PIN PD6 // PD6 +#endif #endif -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#ifdef USE_USART3 +#ifndef UART3_TX_PIN +#define UART3_TX_PIN PB10 // PB10 (AF7) +#endif +#ifndef UART3_RX_PIN +#define UART3_RX_PIN PB11 // PB11 (AF7) +#endif #endif -#ifndef UART4_GPIO -#define UART4_TX_PIN GPIO_Pin_10 // PC10 (AF5) -#define UART4_RX_PIN GPIO_Pin_11 // PC11 (AF5) -#define UART4_GPIO_AF GPIO_AF_5 -#define UART4_GPIO GPIOC -#define UART4_TX_PINSOURCE GPIO_PinSource10 -#define UART4_RX_PINSOURCE GPIO_PinSource11 +#ifdef USE_USART4 +#ifndef UART4_TX_PIN +#define UART4_TX_PIN PC10 // PC10 (AF5) +#endif +#ifndef UART4_RX_PIN +#define UART4_RX_PIN PC11 // PC11 (AF5) +#endif #endif -#ifndef UART5_GPIO // The real UART5_RX is on PD2, no board is using. -#define UART5_TX_PIN GPIO_Pin_12 // PC12 (AF5) -#define UART5_RX_PIN GPIO_Pin_12 // PC12 (AF5) -#define UART5_GPIO_AF GPIO_AF_5 -#define UART5_GPIO GPIOC -#define UART5_TX_PINSOURCE GPIO_PinSource12 -#define UART5_RX_PINSOURCE GPIO_PinSource12 +#ifdef USE_USART5 +#ifndef UART5_TX_PIN // The real UART5_RX is on PD2, no board is using. +#define UART5_TX_PIN PC12 // PC12 (AF5) +#endif +#ifndef UART5_RX_PIN +#define UART5_RX_PIN PC12 // PC12 (AF5) +#endif #endif #ifdef USE_USART1 @@ -105,6 +99,33 @@ static uartPort_t uartPort4; static uartPort_t uartPort5; #endif +void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af) +{ + if (options & SERIAL_BIDIR) { + ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, + (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, + (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP + ); + + IOInit(tx, OWNER_SERIAL_RXTX, RESOURCE_USART); + IOConfigGPIOAF(tx, ioCfg, af); + + if (!(options & SERIAL_INVERTED)) + IOLo(tx); // OpenDrain output should be inactive + } else { + ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP); + if (mode & MODE_TX) { + IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART); + IOConfigGPIOAF(tx, ioCfg, af); + } + + if (mode & MODE_RX) { + IOInit(tx, OWNER_SERIAL_RX, RESOURCE_USART); + IOConfigGPIOAF(rx, ioCfg, af); + } + } +} + #ifdef USE_USART1 uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { @@ -112,7 +133,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort1; s->port.vTable = uartVTable; @@ -134,34 +154,10 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB2(USART1), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART1_GPIO, UART1_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN; - GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART1_RX_PIN; - GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7); // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; @@ -189,7 +185,6 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort2; s->port.vTable = uartVTable; @@ -212,37 +207,13 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_ClockCmd(RCC_APB1(USART2), ENABLE); #if defined(USE_USART2_TX_DMA) || defined(USE_USART2_RX_DMA) - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); #endif - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART2_GPIO, UART2_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN; - GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART2_RX_PIN; - GPIO_PinAFConfig(UART2_GPIO, UART2_RX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7); #ifdef USE_USART2_TX_DMA // DMA TX Interrupt @@ -272,7 +243,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort3; s->port.vTable = uartVTable; @@ -295,37 +265,13 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_ClockCmd(RCC_APB1(USART3), ENABLE); #if defined(USE_USART3_TX_DMA) || defined(USE_USART3_RX_DMA) - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE); #endif - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART3_GPIO, UART3_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN; - GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART3_RX_PIN; - GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7); #ifdef USE_USART3_TX_DMA // DMA TX Interrupt @@ -355,7 +301,6 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE]; static volatile uint8_t tx4Buffer[UART4_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort4; s->port.vTable = uartVTable; @@ -369,33 +314,9 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = UART4; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_ClockCmd(RCC_APB1(UART4), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART4_GPIO, UART4_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN; - GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART4_RX_PIN; - GPIO_PinAFConfig(UART4_GPIO, UART4_RX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5); NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4); @@ -414,7 +335,6 @@ uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t optio static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE]; static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort5; s->port.vTable = uartVTable; @@ -428,33 +348,9 @@ uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = UART5; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_ClockCmd(RCC_APB1(UART5), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART5_GPIO, UART5_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN; - GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART5_RX_PIN; - GPIO_PinAFConfig(UART5_GPIO, UART5_RX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5); NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5); diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 1df1d3c4fd..286cfe9a46 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -74,27 +74,14 @@ #define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_2 // PA2 -#define UART2_RX_PIN GPIO_Pin_3 // PA3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 - -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART2_TX_PIN PA2 // PA2 +#define UART2_RX_PIN PA3 // PA3 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 5e6c1b8ad0..4ca63a6b52 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -74,15 +74,16 @@ #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 4 +#ifdef USE_UART1_RX_DMA +#undef USE_UART1_RX_DMA +#endif + #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 -#define USART3_RX_PIN Pin_11 -#define USART3_TX_PIN Pin_10 -#define USART3_GPIO GPIOB -#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 -#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB +#define USART3_RX_PIN PB11 +#define USART3_TX_PIN PB10 #define USE_SPI #define USE_SPI_DEVICE_1 diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 5e7f79ce05..f3fdecfeee 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -111,7 +111,7 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTE 0xffff #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10)) diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 8fb4cee7a2..e0d102913c 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -82,26 +82,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_4 -#define UART1_RX_PIN GPIO_Pin_5 -#define UART1_GPIO GPIOC -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource4 -#define UART1_RX_PINSOURCE GPIO_PinSource5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN GPIO_Pin_14 -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index c790c52421..c3be09e18f 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -100,32 +100,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -// tqfp48 pin 42 -#define UART1_TX_PIN GPIO_Pin_6 -// tqfp48 pin 43 -#define UART1_RX_PIN GPIO_Pin_7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -// tqfp48 pin 12 -#define UART2_TX_PIN GPIO_Pin_2 -// tqfp48 pin 13 -#define UART2_RX_PIN GPIO_Pin_3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 -// tqfp48 pin 21 -#define UART3_TX_PIN GPIO_Pin_10 -// tqfp48 pin 22 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index db4ddd7457..4c9e1f44e0 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -113,30 +113,14 @@ #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 9588159722..4ff16f5ffa 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -49,30 +49,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 3 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 13550a2545..31bcb82f76 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -23,8 +23,9 @@ #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR) -#define LED0 PB1 +#define LED0 PB1 #define BEEPER PB13 +#define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 @@ -49,26 +50,14 @@ #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_3 -#define UART2_RX_PIN GPIO_Pin_4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 600bd2ee66..4001b733bb 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -62,26 +62,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_4 -#define UART1_RX_PIN GPIO_Pin_5 -#define UART1_GPIO GPIOC -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource4 -#define UART1_RX_PINSOURCE GPIO_PinSource5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN GPIO_Pin_14 -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 183e1326d5..e6ea276d6e 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -68,26 +68,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_3 // PB3 -#define UART2_RX_PIN GPIO_Pin_4 // PB4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 // PB3 +#define UART2_RX_PIN PB4 // PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index cc8b93c09f..f8c8b66420 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -134,11 +134,8 @@ #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 // USART3 only on NAZE32_SP - Flex Port -#define USART3_RX_PIN Pin_11 -#define USART3_TX_PIN Pin_10 -#define USART3_GPIO GPIOB -#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 -#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB +#define USART3_RX_PIN PB11 +#define USART3_TX_PIN PB10 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 76d995fce3..4512142c27 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -76,30 +76,14 @@ #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3 diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 36ee217725..e9eaf65df0 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -54,26 +54,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_3 // PB3 -#define UART2_RX_PIN GPIO_Pin_4 // PB4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 // PB3 +#define UART2_RX_PIN PB4 // PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_SPI #define USE_SPI_DEVICE_2 diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 602609862e..db24488cb2 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -62,30 +62,14 @@ #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 0d89f4226a..8de22972ab 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -49,26 +49,15 @@ #define USE_SOFTSERIAL1 // Telemetry #define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN GPIO_Pin_9 -#define UART1_RX_PIN GPIO_Pin_10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN GPIO_Pin_14 //Not connected -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 //Not connected +#define UART2_RX_PIN PA15 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 #define SOFTSERIAL_1_TIMER TIM15 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 1700d13cf9..c504b58716 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -61,30 +61,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_3 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #undef USE_I2C diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 0913d0ec16..15f7d013cc 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -61,26 +61,14 @@ #define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_2 // PA2 - Clashes with PWM6 input. -#define UART2_RX_PIN GPIO_Pin_3 // PA3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input. +#define UART2_RX_PIN PA3 // PA3 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) // Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP? diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 840dda225a..6cf238c0c7 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -72,30 +72,14 @@ #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 4adbe0d563..d30b46f29a 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -70,30 +70,14 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 4 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 61b4bd9b5e..a1e609d4ac 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -79,30 +79,14 @@ #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3 diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 217765adcf..187ab69115 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -62,30 +62,14 @@ #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_3 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index d8ac143e88..d15f1b2999 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -56,30 +56,12 @@ #define USE_USART3 #define SERIAL_PORT_COUNT 3 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/common.h b/src/main/target/common.h index dbe2c3a374..c9a9a0f1b3 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -36,6 +36,12 @@ #endif +#ifdef STM32F1 +// Using RX DMA disables the use of receive callbacks +#define USE_UART1_RX_DMA + +#endif + #define SERIAL_RX #define USE_CLI From ca0cb73c937d4a00800b0daa7e02548ed551957d Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 4 Jul 2016 22:11:24 +1000 Subject: [PATCH 074/108] removed superfluous functions --- src/main/drivers/pwm_mapping.c | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index fe2c5f24b4..1cf9cd948f 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -93,16 +93,6 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void) return &pwmOutputConfiguration; } -bool CheckGPIOPin(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) -{ - return IO_GPIOBYTAG(tag) == gpio && IO_PINBYTAG(tag) == pin; -} - -bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) -{ - return IO_GPIOBYTAG(tag) == gpio && IO_GPIO_PinSource(IOGetByTag(tag)) == pin; -} - pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) { int i = 0; From c4e75e456c40d8cbc03d69fde16d6f984526b172 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 6 Jul 2016 18:36:25 +1000 Subject: [PATCH 075/108] Move to UART naming convention where possible (rather than USART). --- src/main/config/config.c | 2 +- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/serial_uart.c | 22 ++-- src/main/drivers/serial_uart_impl.h | 12 +- src/main/drivers/serial_uart_stm32f10x.c | 50 ++++---- src/main/drivers/serial_uart_stm32f30x.c | 78 ++++++------ src/main/drivers/serial_uart_stm32f4xx.c | 144 ++++++++++------------ src/main/io/serial.c | 28 ++--- src/main/main.c | 6 +- src/main/target/ALIENFLIGHTF3/target.c | 4 +- src/main/target/ALIENFLIGHTF3/target.h | 6 +- src/main/target/ALIENFLIGHTF4/target.h | 32 ++--- src/main/target/BLUEJAYF4/target.h | 20 +-- src/main/target/CC3D/target.h | 8 +- src/main/target/CHEBUZZF3/target.h | 6 +- src/main/target/CJMCU/target.h | 4 +- src/main/target/COLIBRI_RACE/target.h | 6 +- src/main/target/DOGE/target.h | 6 +- src/main/target/EUSTM32F103RC/target.h | 4 +- src/main/target/FURYF3/target.h | 8 +- src/main/target/FURYF4/target.h | 20 +-- src/main/target/IRCFUSIONF3/target.c | 4 +- src/main/target/IRCFUSIONF3/target.h | 6 +- src/main/target/KISSFC/target.h | 6 +- src/main/target/LUX_RACE/target.h | 6 +- src/main/target/MOTOLAB/target.h | 6 +- src/main/target/NAZE/target.h | 10 +- src/main/target/OLIMEXINO/target.h | 6 +- src/main/target/OMNIBUS/target.c | 4 +- src/main/target/OMNIBUS/target.h | 8 +- src/main/target/PIKOBLX/target.h | 6 +- src/main/target/PORT103R/target.h | 4 +- src/main/target/REVO/target.h | 20 +-- src/main/target/REVONANO/target.h | 12 +- src/main/target/RMDO/target.c | 4 +- src/main/target/RMDO/target.h | 6 +- src/main/target/SINGULARITY/target.h | 6 +- src/main/target/SIRINFPV/target.h | 8 +- src/main/target/SPARKY/target.h | 6 +- src/main/target/SPRACINGF3/target.c | 4 +- src/main/target/SPRACINGF3/target.h | 6 +- src/main/target/SPRACINGF3EVO/target.c | 4 +- src/main/target/SPRACINGF3EVO/target.h | 8 +- src/main/target/SPRACINGF3MINI/target.c | 4 +- src/main/target/SPRACINGF3MINI/target.h | 8 +- src/main/target/STM32F3DISCOVERY/target.h | 6 +- src/main/target/X_RACERSPI/target.c | 4 +- src/main/target/X_RACERSPI/target.h | 6 +- src/main/target/ZCOREF3/target.c | 4 +- src/main/target/ZCOREF3/target.h | 6 +- 50 files changed, 324 insertions(+), 332 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index 003b7c32a7..3d15e233e6 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -835,7 +835,7 @@ void validateAndFixConfig(void) } #endif -#if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3) +#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3) if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) { featureClear(FEATURE_DISPLAY); } diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 1cf9cd948f..2636b61353 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -132,7 +132,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#if defined(STM32F303xC) && defined(USE_USART3) +#if defined(STM32F303xC) && defined(USE_UART3) // skip UART3 ports (PB10/PB11) if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN))) continue; diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 8a7999bea5..3bee96b89e 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -99,26 +99,26 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uartPort_t *s = NULL; if (USARTx == USART1) { - s = serialUSART1(baudRate, mode, options); -#ifdef USE_USART2 + s = serialUART1(baudRate, mode, options); +#ifdef USE_UART2 } else if (USARTx == USART2) { - s = serialUSART2(baudRate, mode, options); + s = serialUART2(baudRate, mode, options); #endif -#ifdef USE_USART3 +#ifdef USE_UART3 } else if (USARTx == USART3) { - s = serialUSART3(baudRate, mode, options); + s = serialUART3(baudRate, mode, options); #endif -#ifdef USE_USART4 +#ifdef USE_UART4 } else if (USARTx == UART4) { - s = serialUSART4(baudRate, mode, options); + s = serialUART4(baudRate, mode, options); #endif -#ifdef USE_USART5 +#ifdef USE_UART5 } else if (USARTx == UART5) { - s = serialUSART5(baudRate, mode, options); + s = serialUART5(baudRate, mode, options); #endif -#ifdef USE_USART6 +#ifdef USE_UART6 } else if (USARTx == USART6) { - s = serialUSART6(baudRate, mode, options); + s = serialUART6(baudRate, mode, options); #endif } else { diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index 5b0c2b3e08..a4549de344 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -23,10 +23,10 @@ extern const struct serialPortVTable uartVTable[]; void uartStartTxDMA(uartPort_t *s); -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options); diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 473689a8bb..f804b7dea6 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -37,19 +37,19 @@ #include "serial_uart.h" #include "serial_uart_impl.h" -#ifdef USE_USART1 +#ifdef USE_UART1 static uartPort_t uartPort1; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartPort_t uartPort2; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartPort_t uartPort3; #endif -void usartIrqCallback(uartPort_t *s) +void uartIrqCallback(uartPort_t *s) { uint16_t SR = s->USARTx->SR; @@ -76,9 +76,9 @@ void usartIrqCallback(uartPort_t *s) } } -#ifdef USE_USART1 +#ifdef USE_UART1 // USART1 - Telemetry (RX/TX by DMA) -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; @@ -99,7 +99,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = USART1; -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; #endif @@ -109,8 +109,8 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio RCC_ClockCmd(RCC_APB2(USART1), ENABLE); RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - // USART1_TX PA9 - // USART1_RX PA10 + // UART1_TX PA9 + // UART1_RX PA10 if (options & SERIAL_BIDIR) { IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_RXTX, RESOURCE_USART); IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD); @@ -133,7 +133,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); -#ifndef USE_USART1_RX_DMA +#ifndef USE_UART1_RX_DMA // RX/TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1); @@ -162,14 +162,14 @@ void DMA1_Channel4_IRQHandler(void) void USART1_IRQHandler(void) { uartPort_t *s = &uartPort1; - usartIrqCallback(s); + uartIrqCallback(s); } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 // USART2 - GPS or Spektrum or ?? (RX + TX by IRQ) -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; @@ -195,8 +195,8 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio RCC_ClockCmd(RCC_APB1(USART2), ENABLE); RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - // USART2_TX PA2 - // USART2_RX PA3 + // UART2_TX PA2 + // UART2_RX PA3 if (options & SERIAL_BIDIR) { IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_RXTX, RESOURCE_USART); IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD); @@ -227,14 +227,14 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio void USART2_IRQHandler(void) { uartPort_t *s = &uartPort2; - usartIrqCallback(s); + uartIrqCallback(s); } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 // USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; @@ -260,17 +260,17 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio RCC_ClockCmd(RCC_APB1(USART3), ENABLE); if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_RXTX, RESOURCE_USART); - IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_OD); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_TX, RESOURCE_USART); - IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_PP); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(USART3_RX_PIN)), OWNER_SERIAL_RX, RESOURCE_USART); - IOConfigGPIO(IOGetByTag(IO_TAG(USART3_RX_PIN)), IOCFG_IPU); + IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL_RX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); } } @@ -288,6 +288,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio void USART3_IRQHandler(void) { uartPort_t *s = &uartPort3; - usartIrqCallback(s); + uartIrqCallback(s); } #endif diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index f8c0c57893..dae0f16555 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -38,7 +38,7 @@ #include "serial_uart.h" #include "serial_uart_impl.h" -#ifdef USE_USART1 +#ifdef USE_UART1 #ifndef UART1_TX_PIN #define UART1_TX_PIN PA9 // PA9 #endif @@ -47,7 +47,7 @@ #endif #endif -#ifdef USE_USART2 +#ifdef USE_UART2 #ifndef UART2_TX_PIN #define UART2_TX_PIN PD5 // PD5 #endif @@ -56,7 +56,7 @@ #endif #endif -#ifdef USE_USART3 +#ifdef USE_UART3 #ifndef UART3_TX_PIN #define UART3_TX_PIN PB10 // PB10 (AF7) #endif @@ -65,7 +65,7 @@ #endif #endif -#ifdef USE_USART4 +#ifdef USE_UART4 #ifndef UART4_TX_PIN #define UART4_TX_PIN PC10 // PC10 (AF5) #endif @@ -74,7 +74,7 @@ #endif #endif -#ifdef USE_USART5 +#ifdef USE_UART5 #ifndef UART5_TX_PIN // The real UART5_RX is on PD2, no board is using. #define UART5_TX_PIN PC12 // PC12 (AF5) #endif @@ -83,19 +83,19 @@ #endif #endif -#ifdef USE_USART1 +#ifdef USE_UART1 static uartPort_t uartPort1; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartPort_t uartPort2; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartPort_t uartPort3; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 static uartPort_t uartPort4; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 static uartPort_t uartPort5; #endif @@ -126,8 +126,8 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui } } -#ifdef USE_USART1 -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART1 +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; @@ -144,7 +144,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; #endif s->txDMAChannel = DMA1_Channel4; @@ -166,7 +166,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); -#ifndef USE_USART1_RX_DMA +#ifndef USE_UART1_RX_DMA NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_RXDMA); @@ -178,8 +178,8 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART2 -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART2 +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; @@ -198,24 +198,24 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = USART2; -#ifdef USE_USART2_RX_DMA +#ifdef USE_UART2_RX_DMA s->rxDMAChannel = DMA1_Channel6; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; #endif -#ifdef USE_USART2_TX_DMA +#ifdef USE_UART2_TX_DMA s->txDMAChannel = DMA1_Channel7; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif RCC_ClockCmd(RCC_APB1(USART2), ENABLE); -#if defined(USE_USART2_TX_DMA) || defined(USE_USART2_RX_DMA) +#if defined(USE_UART2_TX_DMA) || defined(USE_UART2_RX_DMA) RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); #endif serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7); -#ifdef USE_USART2_TX_DMA +#ifdef USE_UART2_TX_DMA // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel7_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_TXDMA); @@ -224,7 +224,7 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio NVIC_Init(&NVIC_InitStructure); #endif -#ifndef USE_USART2_RX_DMA +#ifndef USE_UART2_RX_DMA NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_RXDMA); @@ -236,8 +236,8 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART3 +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; @@ -256,24 +256,24 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = USART3; -#ifdef USE_USART3_RX_DMA +#ifdef USE_UART3_RX_DMA s->rxDMAChannel = DMA1_Channel3; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; #endif -#ifdef USE_USART3_TX_DMA +#ifdef USE_UART3_TX_DMA s->txDMAChannel = DMA1_Channel2; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif RCC_ClockCmd(RCC_APB1(USART3), ENABLE); -#if defined(USE_USART3_TX_DMA) || defined(USE_USART3_RX_DMA) +#if defined(USE_UART3_TX_DMA) || defined(USE_UART3_RX_DMA) RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE); #endif serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7); -#ifdef USE_USART3_TX_DMA +#ifdef USE_UART3_TX_DMA // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel2_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_TXDMA); @@ -282,7 +282,7 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio NVIC_Init(&NVIC_InitStructure); #endif -#ifndef USE_USART3_RX_DMA +#ifndef USE_UART3_RX_DMA NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_RXDMA); @@ -294,8 +294,8 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART4 -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART4 +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE]; @@ -328,8 +328,8 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART5 -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART5 +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE]; @@ -381,7 +381,7 @@ void DMA1_Channel4_IRQHandler(void) handleUsartTxDma(s); } -#ifdef USE_USART2_TX_DMA +#ifdef USE_UART2_TX_DMA // USART2 Tx DMA Handler void DMA1_Channel7_IRQHandler(void) { @@ -393,7 +393,7 @@ void DMA1_Channel7_IRQHandler(void) #endif // USART3 Tx DMA Handler -#ifdef USE_USART3_TX_DMA +#ifdef USE_UART3_TX_DMA void DMA1_Channel2_IRQHandler(void) { uartPort_t *s = &uartPort3; @@ -436,7 +436,7 @@ void usartIrqHandler(uartPort_t *s) } } -#ifdef USE_USART1 +#ifdef USE_UART1 void USART1_IRQHandler(void) { uartPort_t *s = &uartPort1; @@ -445,7 +445,7 @@ void USART1_IRQHandler(void) } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 void USART2_IRQHandler(void) { uartPort_t *s = &uartPort2; @@ -454,7 +454,7 @@ void USART2_IRQHandler(void) } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 void USART3_IRQHandler(void) { uartPort_t *s = &uartPort3; @@ -463,7 +463,7 @@ void USART3_IRQHandler(void) } #endif -#ifdef USE_USART4 +#ifdef USE_UART4 void UART4_IRQHandler(void) { uartPort_t *s = &uartPort4; @@ -472,7 +472,7 @@ void UART4_IRQHandler(void) } #endif -#ifdef USE_USART5 +#ifdef USE_UART5 void UART5_IRQHandler(void) { uartPort_t *s = &uartPort5; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index f5bba84699..9bac1ceeee 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -30,14 +30,6 @@ #include "serial_uart.h" #include "serial_uart_impl.h" -// Using RX DMA disables the use of receive callbacks -//#define USE_USART1_RX_DMA -//#define USE_USART2_RX_DMA -//#define USE_USART3_RX_DMA -//#define USE_USART4_RX_DMA -//#define USE_USART5_RX_DMA -//#define USE_USART6_RX_DMA - #define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE @@ -71,20 +63,20 @@ typedef struct uartDevice_s { } uartDevice_t; //static uartPort_t uartPort[MAX_UARTS]; -#ifdef USE_USART1 +#ifdef USE_UART1 static uartDevice_t uart1 = { .DMAChannel = DMA_Channel_4, .txDMAStream = DMA2_Stream7, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA2_Stream5, #endif .dev = USART1, - .rx = IO_TAG(USART1_RX_PIN), - .tx = IO_TAG(USART1_TX_PIN), + .rx = IO_TAG(UART1_RX_PIN), + .tx = IO_TAG(UART1_TX_PIN), .af = GPIO_AF_USART1, -#ifdef USART1_AHB1_PERIPHERALS - .rcc_ahb1 = USART1_AHB1_PERIPHERALS, +#ifdef UART1_AHB1_PERIPHERALS + .rcc_ahb1 = UART1_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART1), .txIrq = DMA2_Stream7_IRQn, @@ -94,20 +86,20 @@ static uartDevice_t uart1 = }; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartDevice_t uart2 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART2_RX_DMA +#ifdef USE_UART2_RX_DMA .rxDMAStream = DMA1_Stream5, #endif .txDMAStream = DMA1_Stream6, .dev = USART2, - .rx = IO_TAG(USART2_RX_PIN), - .tx = IO_TAG(USART2_TX_PIN), + .rx = IO_TAG(UART2_RX_PIN), + .tx = IO_TAG(UART2_TX_PIN), .af = GPIO_AF_USART2, -#ifdef USART2_AHB1_PERIPHERALS - .rcc_ahb1 = USART2_AHB1_PERIPHERALS, +#ifdef UART2_AHB1_PERIPHERALS + .rcc_ahb1 = UART2_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART2), .txIrq = DMA1_Stream6_IRQn, @@ -117,20 +109,20 @@ static uartDevice_t uart2 = }; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartDevice_t uart3 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART3_RX_DMA +#ifdef USE_UART3_RX_DMA .rxDMAStream = DMA1_Stream1, #endif .txDMAStream = DMA1_Stream3, .dev = USART3, - .rx = IO_TAG(USART3_RX_PIN), - .tx = IO_TAG(USART3_TX_PIN), + .rx = IO_TAG(UART3_RX_PIN), + .tx = IO_TAG(UART3_TX_PIN), .af = GPIO_AF_USART3, -#ifdef USART3_AHB1_PERIPHERALS - .rcc_ahb1 = USART3_AHB1_PERIPHERALS, +#ifdef UART3_AHB1_PERIPHERALS + .rcc_ahb1 = UART3_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART3), .txIrq = DMA1_Stream3_IRQn, @@ -140,20 +132,20 @@ static uartDevice_t uart3 = }; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 static uartDevice_t uart4 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream2, #endif .txDMAStream = DMA1_Stream4, .dev = UART4, - .rx = IO_TAG(USART4_RX_PIN), - .tx = IO_TAG(USART4_TX_PIN), + .rx = IO_TAG(UART4_RX_PIN), + .tx = IO_TAG(UART4_TX_PIN), .af = GPIO_AF_UART4, -#ifdef USART4_AHB1_PERIPHERALS - .rcc_ahb1 = USART4_AHB1_PERIPHERALS, +#ifdef UART4_AHB1_PERIPHERALS + .rcc_ahb1 = UART4_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART4), .txIrq = DMA1_Stream4_IRQn, @@ -163,20 +155,20 @@ static uartDevice_t uart4 = }; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 static uartDevice_t uart5 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream0, #endif .txDMAStream = DMA2_Stream7, .dev = UART5, - .rx = IO_TAG(USART5_RX_PIN), - .tx = IO_TAG(USART5_TX_PIN), + .rx = IO_TAG(UART5_RX_PIN), + .tx = IO_TAG(UART5_TX_PIN), .af = GPIO_AF_UART5, -#ifdef USART5_AHB1_PERIPHERALS - .rcc_ahb1 = USART5_AHB1_PERIPHERALS, +#ifdef UART5_AHB1_PERIPHERALS + .rcc_ahb1 = UART5_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART5), .txIrq = DMA2_Stream7_IRQn, @@ -186,20 +178,20 @@ static uartDevice_t uart5 = }; #endif -#ifdef USE_USART6 +#ifdef USE_UART6 static uartDevice_t uart6 = { .DMAChannel = DMA_Channel_5, -#ifdef USE_USART6_RX_DMA +#ifdef USE_UART6_RX_DMA .rxDMAStream = DMA2_Stream1, #endif .txDMAStream = DMA2_Stream6, .dev = USART6, - .rx = IO_TAG(USART6_RX_PIN), - .tx = IO_TAG(USART6_TX_PIN), + .rx = IO_TAG(UART6_RX_PIN), + .tx = IO_TAG(UART6_TX_PIN), .af = GPIO_AF_USART6, -#ifdef USART6_AHB1_PERIPHERALS - .rcc_ahb1 = USART6_AHB1_PERIPHERALS, +#ifdef UART6_AHB1_PERIPHERALS + .rcc_ahb1 = UART6_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART6), .txIrq = DMA2_Stream6_IRQn, @@ -210,39 +202,39 @@ static uartDevice_t uart6 = #endif static uartDevice_t* uartHardwareMap[] = { -#ifdef USE_USART1 +#ifdef USE_UART1 &uart1, #else NULL, #endif -#ifdef USE_USART2 +#ifdef USE_UART2 &uart2, #else NULL, #endif -#ifdef USE_USART3 +#ifdef USE_UART3 &uart3, #else NULL, #endif -#ifdef USE_USART4 +#ifdef USE_UART4 &uart4, #else NULL, #endif -#ifdef USE_USART5 +#ifdef USE_UART5 &uart5, #else NULL, #endif -#ifdef USE_USART6 +#ifdef USE_UART6 &uart6, #else NULL, #endif }; -void usartIrqHandler(uartPort_t *s) +void uartIrqHandler(uartPort_t *s) { if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) { if (s->port.callback) { @@ -278,7 +270,7 @@ static void handleUsartTxDma(uartPort_t *s) s->txDMAEmpty = true; } -uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; NVIC_InitTypeDef NVIC_InitStructure; @@ -353,10 +345,10 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p return s; } -#ifdef USE_USART1 -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART1 +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_1, baudRate, mode, options); + return serialUART(UARTDEV_1, baudRate, mode, options); } // USART1 Tx DMA Handler @@ -387,15 +379,15 @@ void DMA2_Stream7_IRQHandler(void) void USART1_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 // USART2 - GPS or Spektrum or ?? (RX + TX by IRQ) -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_2, baudRate, mode, options); + return serialUART(UARTDEV_2, baudRate, mode, options); } // USART2 Tx DMA Handler @@ -425,15 +417,15 @@ void DMA1_Stream6_IRQHandler(void) void USART2_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 // USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_3, baudRate, mode, options); + return serialUART(UARTDEV_3, baudRate, mode, options); } // USART3 Tx DMA Handler @@ -463,15 +455,15 @@ void DMA1_Stream3_IRQHandler(void) void USART3_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART4 +#ifdef USE_UART4 // USART4 -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_4, baudRate, mode, options); + return serialUART(UARTDEV_4, baudRate, mode, options); } // USART4 Tx DMA Handler @@ -501,15 +493,15 @@ void DMA1_Stream4_IRQHandler(void) void UART4_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART5 +#ifdef USE_UART5 // USART5 -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_5, baudRate, mode, options); + return serialUART(UARTDEV_5, baudRate, mode, options); } // USART5 Tx DMA Handler @@ -539,15 +531,15 @@ void DMA1_Stream7_IRQHandler(void) void UART5_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART6 +#ifdef USE_UART6 // USART6 -uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_6, baudRate, mode, options); + return serialUART(UARTDEV_6, baudRate, mode, options); } // USART6 Tx DMA Handler @@ -577,6 +569,6 @@ void DMA2_Stream6_IRQHandler(void) void USART6_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 6fbdad7c0c..be6372b479 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -32,7 +32,7 @@ #include "drivers/serial_softserial.h" #endif -#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) || defined(USE_USART4) || defined(USE_USART5) || defined(USE_USART6) +#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) #include "drivers/serial_uart.h" #endif @@ -60,22 +60,22 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = { #ifdef USE_VCP SERIAL_PORT_USB_VCP, #endif -#ifdef USE_USART1 +#ifdef USE_UART1 SERIAL_PORT_USART1, #endif -#ifdef USE_USART2 +#ifdef USE_UART2 SERIAL_PORT_USART2, #endif -#ifdef USE_USART3 +#ifdef USE_UART3 SERIAL_PORT_USART3, #endif -#ifdef USE_USART4 +#ifdef USE_UART4 SERIAL_PORT_USART4, #endif -#ifdef USE_USART5 +#ifdef USE_UART5 SERIAL_PORT_USART5, #endif -#ifdef USE_USART6 +#ifdef USE_UART6 SERIAL_PORT_USART6, #endif #ifdef USE_SOFTSERIAL1 @@ -273,7 +273,7 @@ serialPort_t *openSerialPort( portMode_t mode, portOptions_t options) { -#if (!defined(USE_VCP) && !defined(USE_USART1) && !defined(USE_USART2) && !defined(USE_USART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) +#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) UNUSED(callback); UNUSED(baudRate); UNUSED(mode); @@ -294,32 +294,32 @@ serialPort_t *openSerialPort( serialPort = usbVcpOpen(); break; #endif -#ifdef USE_USART1 +#ifdef USE_UART1 case SERIAL_PORT_USART1: serialPort = uartOpen(USART1, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 case SERIAL_PORT_USART2: serialPort = uartOpen(USART2, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 case SERIAL_PORT_USART3: serialPort = uartOpen(USART3, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 case SERIAL_PORT_USART4: serialPort = uartOpen(UART4, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 case SERIAL_PORT_USART5: serialPort = uartOpen(UART5, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART6 +#ifdef USE_UART6 case SERIAL_PORT_USART6: serialPort = uartOpen(USART6, callback, baudRate, mode, options); break; diff --git a/src/main/main.c b/src/main/main.c index 1d94e96575..455d4b2606 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -275,16 +275,16 @@ void init(void) pwm_params.airplane = true; else pwm_params.airplane = false; -#if defined(USE_USART2) && defined(STM32F10X) +#if defined(USE_UART2) && defined(STM32F10X) pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2); #endif #ifdef STM32F303xC pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3); #endif -#if defined(USE_USART2) && defined(STM32F40_41xxx) +#if defined(USE_UART2) && defined(STM32F40_41xxx) pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2); #endif -#if defined(USE_USART6) && defined(STM32F40_41xxx) +#if defined(USE_UART6) && defined(STM32F40_41xxx) pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6); #endif pwm_params.useVbat = feature(FEATURE_VBAT); diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 57fc417638..2ced9687ac 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -84,7 +84,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // USART3 RX/TX // RX conflicts with PPM port - //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 - //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 + //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, UART3_RX (AF7) - PWM11 + //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, UART3_TX (AF7) - PWM12 }; diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 286cfe9a46..b05cdb33a4 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -69,9 +69,9 @@ #define MAG_AK8963_ALIGN CW0_DEG_FLIP #define USE_VCP -#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7) -#define USE_USART2 // Receiver - RX (PA3) -#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10) +#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7) +#define USE_UART2 // Receiver - RX (PA3) +#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PB6 // PB6 diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 54983b3d2e..909026c021 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -97,26 +97,26 @@ #define USE_VCP -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART2 -#define USART2_RX_PIN PA3 -#define USART2_TX_PIN PA2 //inverter +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 //inverter -//#define USE_USART3 -//#define USART3_RX_PIN PB11 -//#define USART3_TX_PIN PB10 +//#define USE_UART3 +//#define UART3_RX_PIN PB11 +//#define UART3_TX_PIN PB10 -#define USE_USART4 -#define USART4_RX_PIN PC10 -#define USART4_TX_PIN PC11 +#define USE_UART4 +#define UART4_RX_PIN PC10 +#define UART4_TX_PIN PC11 -//#define USE_USART5 -//#define USART5_RX_PIN PD2 -//#define USART5_TX_PIN PC12 +//#define USE_UART5 +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 8d9d1c633a..4c53e1599f 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -95,18 +95,18 @@ //#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_ENABLED -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 4ca63a6b52..a1425bc538 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -69,8 +69,8 @@ #define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART3 +#define USE_UART1 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 4 @@ -82,8 +82,8 @@ #define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_SPI #define USE_SPI_DEVICE_1 diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index f3fdecfeee..52bea95ba2 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -55,7 +55,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -93,8 +93,8 @@ #define MAG_AK8975_ALIGN CW90_DEG_FLIP #define USE_VCP -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 3 #define USE_I2C diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index d92a591ab8..d84e98eae1 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -35,8 +35,8 @@ #define BRUSHED_MOTORS -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 2 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index e0d102913c..65ab62d5d6 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -77,9 +77,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PC4 diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index c3be09e18f..e4c2f76ba0 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -95,9 +95,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PB6 diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 0869dd46b1..ee893670dd 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -76,8 +76,8 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 4c9e1f44e0..e67a920cc6 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -95,7 +95,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -107,9 +107,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 2559e2d27d..b9631d6124 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -106,18 +106,18 @@ #define VBUS_SENSING_PIN PC5 #define VBUS_SENSING_ENABLED -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index e31aa3a7b6..dd87a86410 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -99,8 +99,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 4ff16f5ffa..8e41030edf 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -44,9 +44,9 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 3 #define UART1_TX_PIN PA9 // PA9 diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 31bcb82f76..de059f7b46 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -44,9 +44,9 @@ #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 4001b733bb..ac7d2c06dd 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -57,9 +57,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PC4 diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index e6ea276d6e..8adefc20c8 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -63,9 +63,9 @@ //#define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PB6 // PB6 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index f8c8b66420..adca1659a7 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -119,9 +119,9 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 @@ -134,8 +134,8 @@ #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 // USART3 only on NAZE32_SP - Flex Port -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 3ff23fd8d3..c526310333 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -28,7 +28,7 @@ #ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER // "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit() -#define LED1 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow +#define LED1 PA1 // D3, PA1/UART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow #endif #define GYRO @@ -62,8 +62,8 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index d895b571ce..a41891d696 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -97,8 +97,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) // LED Strip Pad { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 4512142c27..dedb5de7ee 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -70,9 +70,9 @@ #define USB_DETECT_PIN PB5 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 @@ -134,7 +134,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index e9eaf65df0..938af8f98b 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -49,9 +49,9 @@ #define MPU6000_SPI_INSTANCE SPI2 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PB6 // PB6 diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index d5d0850d93..417f889c9f 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -89,8 +89,8 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 2532d43878..05c58aa979 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -74,18 +74,18 @@ #define USE_VCP #define VBUS_SENSING_PIN PC5 -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 14912fffc1..6e461c5eb2 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -62,13 +62,13 @@ #define USE_VCP #define VBUS_SENSING_PIN PA9 -#define USE_USART1 -#define USART1_RX_PIN PB7 -#define USART1_TX_PIN PB6 +#define USE_UART1 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 -#define USE_USART2 -#define USART2_RX_PIN PA3 -#define USART2_TX_PIN PA2 +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 #define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2 diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 1bea16f50c..ee96272c11 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -99,8 +99,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index db24488cb2..14fd760c8e 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -55,9 +55,9 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 8de22972ab..06e9f3cfee 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -43,9 +43,9 @@ #define USE_FLASH_M25P16 #define USE_VCP -#define USE_USART1 // JST-SH Serial - TX (PA9) RX (PA10) -#define USE_USART2 // Input - TX (NC) RX (PA15) -#define USE_USART3 // Solder Pads - TX (PB10) RX (PB11) +#define USE_UART1 // JST-SH Serial - TX (PA9) RX (PA10) +#define USE_UART2 // Input - TX (NC) RX (PA15) +#define USE_UART3 // Solder Pads - TX (PB10) RX (PB11) #define USE_SOFTSERIAL1 // Telemetry #define SERIAL_PORT_COUNT 5 diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index c504b58716..d48e37363c 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -56,9 +56,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PA9 // PA9 @@ -113,7 +113,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 15f7d013cc..f82be07689 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -56,9 +56,9 @@ #define MAG_AK8975_ALIGN CW180_DEG_FLIP #define USE_VCP -#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7) -#define USE_USART2 // Input - RX (PA3) -#define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10) +#define USE_UART1 // Conn 1 - TX (PB6) RX PB7 (AF7) +#define USE_UART2 // Input - RX (PA3) +#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PB6 // PB6 diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index bf2a06da44..ec9176a27f 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -100,8 +100,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, 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, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 6cf238c0c7..2380fd1008 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -65,9 +65,9 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index 171f6be27a..843ad3d9aa 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -91,8 +91,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8 - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index d30b46f29a..0bae984252 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -65,9 +65,9 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PA9 // PA9 @@ -110,7 +110,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 214dab6564..d1e3a0d8b2 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -100,8 +100,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) // LED Strip Pad { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index a1e609d4ac..d76558a9c2 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -73,9 +73,9 @@ #define USB_DETECT_PIN PB5 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 @@ -117,7 +117,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 7664b47e0c..8ac7eca05f 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -112,7 +112,7 @@ //// Divide to under 25MHz for normal operation: //#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 // -//// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +//// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. //#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 //#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -123,8 +123,8 @@ #define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 3 // uart2 gpio for shared serial rx/ppm diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index f2ad959f8d..85db79093c 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -84,8 +84,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 187ab69115..4a38e233fb 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -55,9 +55,9 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c index a3cfdc7339..b72400e6fd 100644 --- a/src/main/target/ZCOREF3/target.c +++ b/src/main/target/ZCOREF3/target.c @@ -83,8 +83,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index d15f1b2999..dc9f80cb23 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -51,9 +51,9 @@ #define BARO #define USE_BARO_BMP280 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 3 From 67d448d8ea30d20d5f571e391fe1adcba606bec1 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 9 Jul 2016 17:03:16 +1000 Subject: [PATCH 076/108] Improved Resource command output. --- src/main/drivers/accgyro_l3gd20.c | 2 +- src/main/drivers/accgyro_mma845x.c | 2 +- src/main/drivers/accgyro_mpu.c | 2 +- src/main/drivers/accgyro_spi_mpu6000.c | 2 +- src/main/drivers/accgyro_spi_mpu6500.c | 2 +- src/main/drivers/accgyro_spi_mpu9250.c | 2 +- src/main/drivers/adc_stm32f10x.c | 2 +- src/main/drivers/adc_stm32f30x.c | 2 +- src/main/drivers/adc_stm32f4xx.c | 2 +- src/main/drivers/barometer_bmp085.c | 2 +- src/main/drivers/barometer_spi_bmp280.c | 2 +- src/main/drivers/bus_i2c_stm32f10x.c | 4 +- src/main/drivers/bus_i2c_stm32f30x.c | 3 ++ src/main/drivers/bus_spi.c | 18 +++----- src/main/drivers/flash_m25p16.c | 2 +- src/main/drivers/inverter.c | 2 +- src/main/drivers/io.c | 25 ++++++++--- src/main/drivers/io.h | 2 +- src/main/drivers/io_impl.h | 3 +- src/main/drivers/light_led.c | 2 +- .../drivers/light_ws2811strip_stm32f10x.c | 2 +- .../drivers/light_ws2811strip_stm32f30x.c | 2 +- .../drivers/light_ws2811strip_stm32f4xx.c | 2 +- src/main/drivers/max7456.c | 5 ++- src/main/drivers/pwm_output.c | 11 ++--- src/main/drivers/pwm_rx.c | 16 +++---- src/main/drivers/resource.h | 43 ++++++++++-------- src/main/drivers/sdcard.c | 6 +-- src/main/drivers/serial_softserial.c | 30 +++++-------- src/main/drivers/serial_uart_stm32f10x.c | 18 ++++---- src/main/drivers/serial_uart_stm32f30x.c | 18 ++++---- src/main/drivers/serial_uart_stm32f4xx.c | 6 +-- src/main/drivers/serial_usb_vcp.c | 4 +- src/main/drivers/sonar_hcsr04.c | 4 +- src/main/drivers/sound_beeper.c | 2 +- src/main/drivers/timer.c | 2 +- src/main/drivers/usb_io.c | 4 +- src/main/io/serial_cli.c | 45 +++++-------------- src/main/rx/spektrum.c | 4 +- .../target/ALIENFLIGHTF3/hardware_revision.c | 2 +- src/main/target/BLUEJAYF4/target.h | 9 +++- 41 files changed, 154 insertions(+), 164 deletions(-) diff --git a/src/main/drivers/accgyro_l3gd20.c b/src/main/drivers/accgyro_l3gd20.c index aade7445b2..e227d7f8d4 100644 --- a/src/main/drivers/accgyro_l3gd20.c +++ b/src/main/drivers/accgyro_l3gd20.c @@ -76,7 +76,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx) UNUSED(SPIx); // FIXME mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN)); - IOInit(mpul3gd20CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpul3gd20CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG); DISABLE_L3GD20; diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 4adbe59ab8..202b90e804 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -105,7 +105,7 @@ static inline void mma8451ConfigureInterrupt(void) // PA5 - ACC_INT2 output on NAZE rev3/4 hardware // NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board // OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code. - IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_SYSTEM, RESOURCE_I2C); + IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0); IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? #endif diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index b52a2fb796..25b31506c7 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -244,7 +244,7 @@ void mpuIntExtiInit(void) } #endif - IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI); + IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 1); IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler); diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index cb78ffe102..b8c1360258 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -159,7 +159,7 @@ bool mpu6000SpiDetect(void) #ifdef MPU6000_CS_PIN mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN)); #endif - IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG); spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 2731797258..32ae6a1ce8 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -69,7 +69,7 @@ static void mpu6500SpiInit(void) } mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN)); - IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpuSpi6500CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG); spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST); diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 95c0b3f50f..3e4d1635c8 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -191,7 +191,7 @@ bool mpu9250SpiDetect(void) #ifdef MPU9250_CS_PIN mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN)); #endif - IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index 9d94742468..dc0598988f 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -123,7 +123,7 @@ void adcInit(drv_adc_config_t *init) if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 0116a6734a..c9ae8dc47e 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -139,7 +139,7 @@ void adcInit(drv_adc_config_t *init) if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i,0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = adcChannelCount++; diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index e0b36a5f33..4466f34430 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -134,7 +134,7 @@ void adcInit(drv_adc_config_t *init) if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 34a01cd38e..ad4c547bf4 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -143,7 +143,7 @@ void bmp085InitXclrIO(const bmp085Config_t *config) { if (!xclrIO && config && config->xclrIO) { xclrIO = IOGetByTag(config->xclrIO); - IOInit(xclrIO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(xclrIO, OWNER_BARO, RESOURCE_OUTPUT, 0); IOConfigGPIO(xclrIO, IOCFG_OUT_PP); } } diff --git a/src/main/drivers/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c index 3838ba4328..d7a7491959 100644 --- a/src/main/drivers/barometer_spi_bmp280.c +++ b/src/main/drivers/barometer_spi_bmp280.c @@ -65,7 +65,7 @@ void bmp280SpiInit(void) } bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN)); - IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI); + IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI_CS, 0); IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP); DISABLE_BMP280; diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 72cf8769c2..14049461ae 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -385,8 +385,8 @@ void i2cInit(I2CDevice device) IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); - IOInit(scl, OWNER_SYSTEM, RESOURCE_I2C); - IOInit(sda, OWNER_SYSTEM, RESOURCE_I2C); + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(i2c->rcc, ENABLE); diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 11704a3f90..39cdb3b234 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -92,7 +92,10 @@ void i2cInit(I2CDevice device) RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); + + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 90224cefcc..b3b3f992bf 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -113,19 +113,13 @@ void spiInitDevice(SPIDevice device) RCC_ClockCmd(spi->rcc, ENABLE); RCC_ResetCmd(spi->rcc, ENABLE); - IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI); + IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); + IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); + IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); -#if defined(STM32F303xC) || defined(STM32F4) - if (spi->sdcard) { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); - } - else { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); - } +#if defined(STM32F3) || defined(STM32F4) + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); if (spi->nss) diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 1063debae6..f4111e8259 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -203,7 +203,7 @@ bool m25p16_init() #ifdef M25P16_CS_PIN m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN)); #endif - IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI); + IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0); IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG); DISABLE_M25P16; diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index e0231ddb78..0b31d5d8e6 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -31,7 +31,7 @@ static const IO_t pin = DEFIO_IO(INVERTER); void initInverter(void) { - IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0); IOConfigGPIO(pin, IOCFG_OUT_PP); inverterSet(false); diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 11562cfc98..bdfd137f63 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -53,6 +53,19 @@ const struct ioPortDef_s ioPortDefs[] = { }; # endif +const char * const ownerNames[OWNER_TOTAL_COUNT] = { + "FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER", + "SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD", + "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", +}; + +const char * const resourceNames[RESOURCE_TOTAL_COUNT] = { + "", // NONE + "IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL", + "SDA", "SCK","MOSI","MISO","CS","BATTERY","RSSI","EXT","CURRENT" +}; + + ioRec_t* IO_Rec(IO_t io) { return io; @@ -190,12 +203,12 @@ void IOToggle(IO_t io) } // claim IO pin, set owner and resources -void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources) +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index) { ioRec_t *ioRec = IO_Rec(io); - if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner - ioRec->owner = owner; - ioRec->resourcesUsed |= resources; + ioRec->owner = owner; + ioRec->resource = resource; + ioRec->index = index; } void IORelease(IO_t io) @@ -210,10 +223,10 @@ resourceOwner_t IOGetOwner(IO_t io) return ioRec->owner; } -resourceType_t IOGetResources(IO_t io) +resourceType_t IOGetResource(IO_t io) { ioRec_t *ioRec = IO_Rec(io); - return ioRec->resourcesUsed; + return ioRec->resource; } #if defined(STM32F1) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 315560e430..07c53a2032 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -86,7 +86,7 @@ void IOHi(IO_t io); void IOLo(IO_t io); void IOToggle(IO_t io); -void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources); +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index); void IORelease(IO_t io); // unimplemented resourceOwner_t IOGetOwner(IO_t io); resourceType_t IOGetResources(IO_t io); diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 3a084949fe..bed28dab33 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -12,7 +12,8 @@ typedef struct ioRec_s { GPIO_TypeDef *gpio; uint16_t pin; resourceOwner_t owner; - resourceType_t resourcesUsed; // TODO! + resourceType_t resource; + uint8_t index; } ioRec_t; extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 15075580b6..80582c1fa1 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -97,7 +97,7 @@ void ledInit(bool alternative_led) for (i = 0; i < LED_NUMBER; i++) { if (leds[i + ledOffset]) { - IOInit(leds[i + ledOffset], OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); } } diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 40003663d9..863dd24ea0 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -53,7 +53,7 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 567fd0b8e5..b27e30e51e 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -64,7 +64,7 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index f1d04dfbee..cfde3411c4 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -69,7 +69,7 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); // Stop timer diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index d3efe7e7d2..d71a933a5b 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -49,7 +49,8 @@ static uint8_t video_signal_type = 0; static uint8_t max7456_lock = 0; static IO_t max7456CsPin = IO_NONE; -uint8_t max7456_send(uint8_t add, uint8_t data) { +uint8_t max7456_send(uint8_t add, uint8_t data) +{ spiTransferByte(MAX7456_SPI_INSTANCE, add); return spiTransferByte(MAX7456_SPI_INSTANCE, data); } @@ -64,7 +65,7 @@ void max7456_init(uint8_t video_system) #ifdef MAX7456_SPI_CS_PIN max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN)); #endif - IOInit(max7456CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(max7456CsPin, OWNER_OSD, RESOURCE_SPI_CS, 0); IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG); //Minimum spi clock period for max7456 is 100ns (10Mhz) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 277b47736d..f9feb1a469 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -84,18 +84,15 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8 } } -static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) -{ - IOInit(IOGetByTag(pin), OWNER_PWMOUTPUT_MOTOR, RESOURCE_OUTPUT); - IOConfigGPIO(IOGetByTag(pin), mode); -} - static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value) { pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; configTimeBase(timerHardware->tim, period, mhz); - pwmGPIOConfig(timerHardware->tag, IOCFG_AF_PP); + + IO_t io = IOGetByTag(timerHardware->tag); + IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); + IOConfigGPIO(io, IOCFG_AF_PP); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 856613d2b3..7250c6e795 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -337,12 +337,6 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture } } -static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) -{ - IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT); - IOConfigGPIO(IOGetByTag(pin), mode); -} - void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) { TIM_ICInitTypeDef TIM_ICInitStructure; @@ -372,7 +366,10 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode); + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); + IOConfigGPIO(io, timerHardwarePtr->ioMode); + pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ); @@ -401,7 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->tag, timerHardwarePtr->ioMode); + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); + IOConfigGPIO(io, timerHardwarePtr->ioMode); + pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index a81739bf12..5991f369bf 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -1,46 +1,51 @@ #pragma once +#define RESOURCE_INDEX(x) x + 1 + typedef enum { OWNER_FREE = 0, OWNER_PWMINPUT, OWNER_PPMINPUT, - OWNER_PWMOUTPUT_MOTOR, - OWNER_PWMOUTPUT_SERVO, - OWNER_SOFTSERIAL_RX, - OWNER_SOFTSERIAL_TX, - OWNER_SOFTSERIAL_RXTX, // bidirectional pin for softserial - OWNER_SOFTSERIAL_AUXTIMER, // timer channel is used for softserial. No IO function on pin + OWNER_MOTOR, + OWNER_SERVO, + OWNER_SOFTSERIAL, OWNER_ADC, - OWNER_SERIAL_RX, - OWNER_SERIAL_TX, - OWNER_SERIAL_RXTX, + OWNER_SERIAL, OWNER_PINDEBUG, OWNER_TIMER, OWNER_SONAR, OWNER_SYSTEM, + OWNER_SPI, + OWNER_I2C, OWNER_SDCARD, OWNER_FLASH, OWNER_USB, OWNER_BEEPER, OWNER_OSD, OWNER_BARO, + OWNER_MPU, + OWNER_INVERTER, + OWNER_LED_STRIP, + OWNER_LED, + OWNER_RX, OWNER_TOTAL_COUNT } resourceOwner_t; +extern const char * const ownerNames[OWNER_TOTAL_COUNT]; + // Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function) // with mode switching (shared serial ports, ...) this will need some improvement typedef enum { RESOURCE_NONE = 0, - RESOURCE_INPUT = 1 << 0, - RESOURCE_OUTPUT = 1 << 1, - RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT, - RESOURCE_TIMER = 1 << 2, - RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too - RESOURCE_USART = 1 << 4, - RESOURCE_ADC = 1 << 5, - RESOURCE_EXTI = 1 << 6, - RESOURCE_I2C = 1 << 7, - RESOURCE_SPI = 1 << 8, + RESOURCE_INPUT, RESOURCE_OUTPUT, RESOURCE_IO, + RESOURCE_TIMER, + RESOURCE_UART_TX, RESOURCE_UART_RX, RESOURCE_UART_TXRX, + RESOURCE_EXTI, + RESOURCE_I2C_SCL, RESOURCE_I2C_SDA, + RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS, + RESOURCE_ADC_BATTERY, RESOURCE_ADC_RSSI, RESOURCE_ADC_EXTERNAL1, RESOURCE_ADC_CURRENT, + RESOURCE_TOTAL_COUNT } resourceType_t; +extern const char * const resourceNames[RESOURCE_TOTAL_COUNT]; diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index d5ac385e42..852c4adcf2 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void) { #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); - IOInit(sdCardDetectPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0); IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); #endif } @@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void) { #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); - IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT); + IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0); IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); #endif } @@ -547,7 +547,7 @@ void sdcard_init(bool useDMA) #ifdef SDCARD_SPI_CS_PIN sdCardCsPin = IOGetByTag(IO_TAG(SDCARD_SPI_CS_PIN)); - IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI); + IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0); IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG); #endif // SDCARD_SPI_CS_PIN diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index da2c032681..082fddf9c6 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -100,19 +100,20 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) } } -static void softSerialGPIOConfig(ioTag_t pin, ioConfig_t mode) +void serialInputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL_RXTX, RESOURCE_USART); - IOConfigGPIO(IOGetByTag(pin), mode); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); +#ifdef STM32F1 + IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); +#else + IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); +#endif } -void serialInputPortConfig(ioTag_t pin) +static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex) { -#ifdef STM32F1 - softSerialGPIOConfig(pin, IOCFG_IPU); -#else - softSerialGPIOConfig(pin, IOCFG_AF_PP_UP); -#endif + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); + IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); } static bool isTimerPeriodTooLarge(uint32_t timerPeriod) @@ -164,11 +165,6 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); } -static void serialOutputPortConfig(ioTag_t pin) -{ - softSerialGPIOConfig(pin, IOCFG_OUT_PP); -} - static void resetBuffers(softSerial_t *softSerial) { softSerial->port.rxBufferSize = SOFTSERIAL_BUFFER_SIZE; @@ -219,10 +215,10 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->softSerialPortIndex = portIndex; softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); - serialOutputPortConfig(softSerial->txTimerHardware->tag); + serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex); softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); - serialInputPortConfig(softSerial->rxTimerHardware->tag); + serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); setTxSignal(softSerial, ENABLE); delay(50); @@ -271,8 +267,6 @@ void processTxState(softSerial_t *softSerial) softSerial->isTransmittingData = false; } - - enum { TRAILING, LEADING diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index f804b7dea6..8e73277fcd 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -112,16 +112,16 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option // UART1_TX PA9 // UART1_RX PA10 if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TXRX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL, RESOURCE_UART_RX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU); } } @@ -198,16 +198,16 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option // UART2_TX PA2 // UART2_RX PA3 if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TXRX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } @@ -260,16 +260,16 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB1(USART3), ENABLE); if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_RXTX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL_RX, RESOURCE_USART); + IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); } } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index dae0f16555..a7a3f004bf 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -99,7 +99,7 @@ static uartPort_t uartPort4; static uartPort_t uartPort5; #endif -void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af) +void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) { if (options & SERIAL_BIDIR) { ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, @@ -107,7 +107,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP ); - IOInit(tx, OWNER_SERIAL_RXTX, RESOURCE_USART); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, index); IOConfigGPIOAF(tx, ioCfg, af); if (!(options & SERIAL_INVERTED)) @@ -115,12 +115,12 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui } else { ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP); if (mode & MODE_TX) { - IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(tx, ioCfg, af); } if (mode & MODE_RX) { - IOInit(tx, OWNER_SERIAL_RX, RESOURCE_USART); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(rx, ioCfg, af); } } @@ -157,7 +157,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB2(USART1), ENABLE); RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7); + serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1); // DMA TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; @@ -213,7 +213,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); #endif - serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7); + serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2); #ifdef USE_UART2_TX_DMA // DMA TX Interrupt @@ -271,7 +271,7 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE); #endif - serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7); + serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7, 3); #ifdef USE_UART3_TX_DMA // DMA TX Interrupt @@ -316,7 +316,7 @@ uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB1(UART4), ENABLE); - serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5); + serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5, 4); NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4); @@ -350,7 +350,7 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB1(UART5), ENABLE); - serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5); + serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5); NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5); diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 9bac1ceeee..40f7a919ea 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -312,17 +312,17 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE); if (options & SERIAL_BIDIR) { - IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); } else { if (mode & MODE_TX) { - IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); } if (mode & MODE_RX) { - IOInit(rx, OWNER_SERIAL_RX, RESOURCE_USART); + IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } } diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index bb74b36b3d..f489b16d30 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -181,8 +181,8 @@ serialPort_t *usbVcpOpen(void) vcpPort_t *s; #ifdef STM32F4 - IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO); - IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO); + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_INPUT, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_OUTPUT, 0); USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); #else Set_System(); diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 3b8ec91f7e..0cf058a8a2 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -83,12 +83,12 @@ void hcsr04_init(sonarRange_t *sonarRange) // trigger pin triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); - IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT); + IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); // echo pin echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); - IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT); + IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); #ifdef USE_EXTI diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index cba9a2a5c4..0c60ca4eb4 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -61,7 +61,7 @@ void beeperInit(const beeperConfig_t *config) beeperInverted = config->isInverted; if (beeperIO) { - IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT); + IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT, 0); IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); } systemBeep(false); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index e168a46dfe..7938b9a5be 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -374,7 +374,7 @@ void timerChClearCCFlag(const timerHardware_t *timHw) // configure timer channel GPIO mode void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode) { - IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER); + IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER, 0); IOConfigGPIO(IOGetByTag(timHw->tag), mode); } diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index 51ac90ad4f..14a01bcd65 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -36,7 +36,7 @@ static IO_t usbDetectPin = IO_NONE; void usbCableDetectDeinit(void) { #ifdef USB_DETECT_PIN - IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE); + IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE, 0); IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING); usbDetectPin = IO_NONE; #endif @@ -47,7 +47,7 @@ void usbCableDetectInit(void) #ifdef USB_DETECT_PIN usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN)); - IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT); + IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT, 0); IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP); #endif } diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index e160869df0..0133d359a0 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -3074,47 +3074,22 @@ void cliProcess(void) } } -const char * const ownerNames[OWNER_TOTAL_COUNT] = { - "FREE", - "PWM IN", - "PPM IN", - "MOTOR", - "SERVO", - "SOFTSERIAL RX", - "SOFTSERIAL TX", - "SOFTSERIAL RXTX", // bidirectional pin for softserial - "SOFTSERIAL AUXTIMER", // timer channel is used for softserial. No IO function on pin - "ADC", - "SERIAL RX", - "SERIAL TX", - "SERIAL RXTX", - "PINDEBUG", - "TIMER", - "SONAR", - "SYSTEM", - "SDCARD", - "FLASH", - "USB", - "BEEPER", - "OSD", - "BARO", -}; - static void cliResource(char *cmdline) { UNUSED(cmdline); - cliPrintf("IO:\r\n"); + cliPrintf("IO:\r\n----------------------\r\n"); for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) { const char* owner; - char buff[15]; - if (ioRecs[i].owner < ARRAYLEN(ownerNames)) { - owner = ownerNames[ioRecs[i].owner]; + owner = ownerNames[ioRecs[i].owner]; + + const char* resource; + resource = resourceNames[ioRecs[i].resource]; + + if (ioRecs[i].index > 0) { + cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource); + } else { + cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource); } - else { - sprintf(buff, "O=%d", ioRecs[i].owner); - owner = buff; - } - cliPrintf("%c%02d: %19s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner); } } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 9c0f211028..ef6a8fa3dc 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -184,7 +184,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind) { #ifdef HARDWARE_BIND_PLUG BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN)); - IOInit(BindPlug, OWNER_SYSTEM, RESOURCE_INPUT); + IOInit(BindPlug, OWNER_RX, RESOURCE_INPUT, 0); IOConfigGPIO(BindPlug, IOCFG_IPU); // Check status of bind plug and exit if not active @@ -216,7 +216,7 @@ void spektrumBind(rxConfig_t *rxConfig) LED1_ON; BindPin = IOGetByTag(IO_TAG(BIND_PIN)); - IOInit(BindPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(BindPin, OWNER_RX, RESOURCE_OUTPUT, 0); IOConfigGPIO(BindPin, IOCFG_OUT_PP); // RX line, set high diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c index b51d38658f..a8f1ebdb7e 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.c +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c @@ -40,7 +40,7 @@ static IO_t HWDetectPin = IO_NONE; void detectHardwareRevision(void) { HWDetectPin = IOGetByTag(IO_TAG(HW_PIN)); - IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT); + IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0); IOConfigGPIO(HWDetectPin, IOCFG_IPU); // Check hardware revision diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 4c53e1599f..4d3b7a58a9 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -108,7 +108,13 @@ #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 4 +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 5 + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 + #define USE_ESCSERIAL #define ESCSERIAL_TIMER_TX_HARDWARE 0 @@ -160,3 +166,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9)) + From 93ca58fb8513cbc56ba7bfad34120e0694ee2476 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 9 Jul 2016 17:09:50 +1000 Subject: [PATCH 077/108] MPU index is not required. --- src/main/drivers/accgyro_mpu.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 25b31506c7..ca684aa6ea 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -244,7 +244,7 @@ void mpuIntExtiInit(void) } #endif - IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 1); + IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0); IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler); From f0676b1b7477fb81b28c9fc6cb13e54ac02a435e Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 9 Jul 2016 17:22:47 +1000 Subject: [PATCH 078/108] Added resource details for SIRIN TX. --- src/main/drivers/io.c | 2 +- src/main/drivers/resource.h | 1 + src/main/drivers/vtx_soft_spi_rtc6705.c | 10 +++++----- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index bdfd137f63..980168abba 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -56,7 +56,7 @@ const struct ioPortDef_s ioPortDefs[] = { const char * const ownerNames[OWNER_TOTAL_COUNT] = { "FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER", "SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD", - "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", + "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER" }; const char * const resourceNames[RESOURCE_TOTAL_COUNT] = { diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index 5991f369bf..a177dab1da 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -29,6 +29,7 @@ typedef enum { OWNER_LED_STRIP, OWNER_LED, OWNER_RX, + OWNER_TX, OWNER_TOTAL_COUNT } resourceOwner_t; diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c index cdeb23d5b4..6516183ed1 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.c +++ b/src/main/drivers/vtx_soft_spi_rtc6705.c @@ -53,19 +53,19 @@ static IO_t rtc6705DataPin = IO_NONE; static IO_t rtc6705LePin = IO_NONE; static IO_t rtc6705ClkPin = IO_NONE; -void rtc6705_soft_spi_init(void) { - +void rtc6705_soft_spi_init(void) +{ rtc6705DataPin = IOGetByTag(IO_TAG(RTC6705_SPIDATA_PIN)); rtc6705LePin = IOGetByTag(IO_TAG(RTC6705_SPILE_PIN)); rtc6705ClkPin = IOGetByTag(IO_TAG(RTC6705_SPICLK_PIN)); - IOInit(rtc6705DataPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705DataPin, OWNER_TX, RESOURCE_SPI_MOSI, 0); IOConfigGPIO(rtc6705DataPin, IOCFG_OUT_PP); - IOInit(rtc6705LePin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705LePin, OWNER_TX, RESOURCE_SPI_CS, 0); IOConfigGPIO(rtc6705LePin, IOCFG_OUT_PP); - IOInit(rtc6705ClkPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705ClkPin, OWNER_TX, RESOURCE_SPI_SCK, 0); IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP); } From 98743fea0bc443bed56c142cc31ebbe27bdbc0df Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 9 Jul 2016 17:31:12 +1000 Subject: [PATCH 079/108] Small formatting adjustment --- src/main/drivers/vtx_soft_spi_rtc6705.c | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c index 6516183ed1..6572540c66 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.c +++ b/src/main/drivers/vtx_soft_spi_rtc6705.c @@ -69,7 +69,8 @@ void rtc6705_soft_spi_init(void) IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP); } -static void rtc6705_write_register(uint8_t addr, uint32_t data) { +static void rtc6705_write_register(uint8_t addr, uint32_t data) +{ uint8_t i; RTC6705_SPILE_OFF; @@ -107,7 +108,8 @@ static void rtc6705_write_register(uint8_t addr, uint32_t data) { } -void rtc6705_soft_spi_set_channel(uint16_t channel_freq) { +void rtc6705_soft_spi_set_channel(uint16_t channel_freq) +{ uint32_t freq = (uint32_t)channel_freq * 1000; uint32_t N, A; @@ -119,7 +121,8 @@ void rtc6705_soft_spi_set_channel(uint16_t channel_freq) { rtc6705_write_register(1, (N << 7) | A); } -void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) { +void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) +{ rtc6705_write_register(7, (reduce_power ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT)); } From 62354c1745199aa69694353d935d4affd9bc5858 Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Sat, 9 Jul 2016 13:46:33 +0200 Subject: [PATCH 080/108] PORT103R build failed, updated flash size to 256k. --- src/main/target/PORT103R/target.mk | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/PORT103R/target.mk b/src/main/target/PORT103R/target.mk index 411a04e02b..2246dc6051 100644 --- a/src/main/target/PORT103R/target.mk +++ b/src/main/target/PORT103R/target.mk @@ -1,4 +1,7 @@ F1_TARGETS += $(TARGET) +256K_TARGETS += $(TARGET) +FLASH_SIZE = 256 + FEATURES = ONBOARDFLASH HIGHEND DEVICE_FLAGS = -DSTM32F10X_HD From 3a0f8388ee8befad000de0e8b2382afadb1897b0 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 9 Jul 2016 13:29:01 +0100 Subject: [PATCH 081/108] Changed tabs to spaces in io/ --- src/main/io/asyncfatfs/asyncfatfs.c | 2 +- src/main/io/beeper.c | 4 +- src/main/io/beeper.h | 4 +- src/main/io/gps.c | 64 ++++++++++++++--------------- src/main/io/ledstrip.c | 36 ++++++++-------- src/main/io/rc_controls.c | 6 +-- src/main/io/serial_4way.c | 2 +- src/main/io/serial_4way_stk500v2.c | 6 +-- src/main/io/serial_cli.c | 50 +++++++++++----------- src/main/io/serial_msp.c | 2 +- src/main/io/vtx.c | 2 +- src/main/io/vtx.h | 10 ++--- 12 files changed, 94 insertions(+), 94 deletions(-) diff --git a/src/main/io/asyncfatfs/asyncfatfs.c b/src/main/io/asyncfatfs/asyncfatfs.c index 0fc5c23b97..57b8f0c861 100644 --- a/src/main/io/asyncfatfs/asyncfatfs.c +++ b/src/main/io/asyncfatfs/asyncfatfs.c @@ -2912,7 +2912,7 @@ bool afatfs_chdir(afatfsFilePtr_t directory) afatfs_initFileHandle(&afatfs.currentDirectory); afatfs.currentDirectory.mode = AFATFS_FILE_MODE_READ | AFATFS_FILE_MODE_WRITE; - + if (afatfs.filesystemType == FAT_FILESYSTEM_TYPE_FAT16) afatfs.currentDirectory.type = AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY; else diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index f1ac9e3520..716cf84b36 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -172,7 +172,7 @@ typedef struct beeperTableEntry_s { { BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 16, NULL, "SYSTEM_INIT") }, { BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") }, - { BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") }, + { BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") }, { BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERRED") }, }; @@ -308,7 +308,7 @@ void beeperUpdate(void) if (!beeperIsOn) { beeperIsOn = 1; if (currentBeeperEntry->sequence[beeperPos] != 0) { - if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1)))) + if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1)))) BEEP_ON; warningLedEnable(); warningLedRefresh(); diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 0f9f488ef6..b4ed924130 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -29,7 +29,7 @@ typedef enum { BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats) BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats) - BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB **** + BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB **** BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation @@ -40,7 +40,7 @@ typedef enum { BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on BEEPER_USB, // Some boards have beeper powered USB connected - BEEPER_ALL, // Turn ON or OFF all beeper conditions + BEEPER_ALL, // Turn ON or OFF all beeper conditions BEEPER_PREFERENCE, // Save prefered beeper configuration // BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum } beeperMode_e; diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 3c71c48be8..3006d09114 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -239,7 +239,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) // only RX is needed for NMEA-style GPS #if !defined(COLIBRI_RACE) || !defined(LUX_RACE) if (gpsConfig->provider == GPS_NMEA) - mode &= ~MODE_TX; + mode &= ~MODE_TX; #endif // no callback - buffer will be consumed in gpsThread() @@ -256,47 +256,47 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) void gpsInitNmea(void) { #if defined(COLIBRI_RACE) || defined(LUX_RACE) - uint32_t now; + uint32_t now; #endif switch(gpsData.state) { case GPS_INITIALIZING: #if defined(COLIBRI_RACE) || defined(LUX_RACE) - now = millis(); - if (now - gpsData.state_ts < 1000) - return; - gpsData.state_ts = now; - if (gpsData.state_position < 1) { - serialSetBaudRate(gpsPort, 4800); - gpsData.state_position++; - } else if (gpsData.state_position < 2) { - // print our FIXED init string for the baudrate we want to be at - serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n"); - gpsData.state_position++; - } else { - // we're now (hopefully) at the correct rate, next state will switch to it - gpsSetState(GPS_CHANGE_BAUD); - } - break; + now = millis(); + if (now - gpsData.state_ts < 1000) + return; + gpsData.state_ts = now; + if (gpsData.state_position < 1) { + serialSetBaudRate(gpsPort, 4800); + gpsData.state_position++; + } else if (gpsData.state_position < 2) { + // print our FIXED init string for the baudrate we want to be at + serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n"); + gpsData.state_position++; + } else { + // we're now (hopefully) at the correct rate, next state will switch to it + gpsSetState(GPS_CHANGE_BAUD); + } + break; #endif case GPS_CHANGE_BAUD: #if defined(COLIBRI_RACE) || defined(LUX_RACE) - now = millis(); - if (now - gpsData.state_ts < 1000) - return; - gpsData.state_ts = now; - if (gpsData.state_position < 1) { - serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); - gpsData.state_position++; - } else if (gpsData.state_position < 2) { - serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n"); - gpsData.state_position++; - } else { + now = millis(); + if (now - gpsData.state_ts < 1000) + return; + gpsData.state_ts = now; + if (gpsData.state_position < 1) { + serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); + gpsData.state_position++; + } else if (gpsData.state_position < 2) { + serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n"); + gpsData.state_position++; + } else { #else serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); #endif gpsSetState(GPS_RECEIVING_DATA); #if defined(COLIBRI_RACE) || defined(LUX_RACE) - } + } #endif break; } @@ -1066,7 +1066,7 @@ static void gpsHandlePassthrough(uint8_t data) updateDisplay(); } #endif - + } @@ -1083,7 +1083,7 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) displayShowFixedPage(PAGE_GPS); } #endif - + serialPassthrough(gpsPort, gpsPassthroughPort, &gpsHandlePassthrough, NULL); } diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 863f3a8b6b..e74ca001a0 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -273,16 +273,16 @@ const ledConfig_t defaultLedStripConfig[] = { }; #elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG) const ledConfig_t defaultLedStripConfig[] = { - { CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, }; #else const ledConfig_t defaultLedStripConfig[] = { @@ -370,8 +370,8 @@ static const uint16_t functionMappings[FUNCTION_COUNT] = { LED_FUNCTION_FLIGHT_MODE, LED_FUNCTION_ARM_STATE, LED_FUNCTION_THROTTLE, - LED_FUNCTION_THRUST_RING, - LED_FUNCTION_COLOR + LED_FUNCTION_THRUST_RING, + LED_FUNCTION_COLOR }; // grid offsets @@ -938,7 +938,7 @@ static void applyLedAnimationLayer(void) void updateLedStrip(void) { - if (!(ledStripInitialised && isWS2811LedStripReady())) { + if (!(ledStripInitialised && isWS2811LedStripReady())) { return; } @@ -950,11 +950,11 @@ void updateLedStrip(void) } else { ledStripEnabled = true; } - + if (!ledStripEnabled){ return; } - + uint32_t now = micros(); @@ -1115,8 +1115,8 @@ void ledStripEnable(void) static void ledStripDisable(void) { - setStripColor(&hsv_black); - - ws2811UpdateStrip(); + setStripColor(&hsv_black); + + ws2811UpdateStrip(); } #endif diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index fdea810034..68896a9a89 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -328,12 +328,12 @@ bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationC for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) { modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index]; - + if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) { return true; } } - + return false; } @@ -607,7 +607,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position) switch(adjustmentFunction) { case ADJUSTMENT_RATE_PROFILE: if (getCurrentControlRateProfile() != position) { - changeControlRateProfile(position); + changeControlRateProfile(position); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position); applied = true; } diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index bcea2f8a1e..7b783422fa 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -380,7 +380,7 @@ void esc4wayProcess(serialPort_t *serial) writeByte(crcOut >> 8); writeByte(crcOut & 0xff); serialEndWrite(port); - + #ifdef STM32F4 delay(50); #endif diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c index 872e8dce7d..9c81c89317 100644 --- a/src/main/io/serial_4way_stk500v2.c +++ b/src/main/io/serial_4way_stk500v2.c @@ -89,7 +89,7 @@ static uint8_t ckSumOut; static void StkSendByte(uint8_t dat) { ckSumOut ^= dat; - for (uint8_t i = 0; i < 8; i++) { + for (uint8_t i = 0; i < 8; i++) { if (dat & 0x01) { // 1-bits are encoded as 64.0us high, 72.8us low (135.8us total). ESC_SET_HI; @@ -248,9 +248,9 @@ static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t add StkSendByte(4); // NumTX StkSendByte(4); // NumRX StkSendByte(0); // RxStartAdr - StkSendByte(subcmd); // {TxData} Cmd + StkSendByte(subcmd); // {TxData} Cmd StkSendByte(addr >> 8); // {TxData} AdrHi - StkSendByte(addr & 0xff); // {TxData} AdrLow + StkSendByte(addr & 0xff); // {TxData} AdrLow StkSendByte(0); // {TxData} 0 StkSendPacketFooter(); if (StkRcvPacket(stkInBuf, sizeof(stkInBuf))) { // NumRX + 3 diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 0133d359a0..8f8bad45d9 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -1983,7 +1983,7 @@ static void cliDump(char *cmdline) cliPrintf("%s\r\n", ftoa(yaw, buf)); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } #ifdef USE_SERVOS @@ -2008,7 +2008,7 @@ static void cliDump(char *cmdline) #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } #endif @@ -2023,7 +2023,7 @@ static void cliDump(char *cmdline) cliPrintf("feature -%s\r\n", featureNames[i]); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } for (i = 0; ; i++) { // reenable what we want. if (featureNames[i] == NULL) @@ -2032,7 +2032,7 @@ static void cliDump(char *cmdline) cliPrintf("feature %s\r\n", featureNames[i]); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } @@ -2094,7 +2094,7 @@ static void cliDump(char *cmdline) cliPrintf("smix reverse %d %d r\r\n", i , channel); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } } } @@ -2111,7 +2111,7 @@ static void cliDump(char *cmdline) cliPrint("\r\n# rxfail\r\n"); cliRxFail(""); - + if (dumpMask & DUMP_ALL) { uint8_t activeProfile = masterConfig.current_profile_index; uint8_t profileCount; @@ -2129,7 +2129,7 @@ static void cliDump(char *cmdline) cliRateProfile(""); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } cliPrint("\r\n# restore original profile selection\r\n"); @@ -2158,7 +2158,7 @@ void cliDumpProfile(uint8_t profileIndex) { if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values return; - + changeProfile(profileIndex); cliPrint("\r\n# profile\r\n"); cliProfile(""); @@ -2174,7 +2174,7 @@ void cliDumpRateProfile(uint8_t rateProfileIndex) { if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values return; - + changeControlRateProfile(rateProfileIndex); cliPrint("\r\n# rateprofile\r\n"); cliRateProfile(""); @@ -2551,7 +2551,7 @@ static void cliProfile(char *cmdline) static void cliRateProfile(char *cmdline) { int i; - + if (isEmpty(cmdline)) { cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile()); return; @@ -2566,18 +2566,18 @@ static void cliRateProfile(char *cmdline) { static void cliReboot(void) { - cliRebootEx(false); + cliRebootEx(false); } static void cliRebootEx(bool bootLoader) { - cliPrint("\r\nRebooting"); + cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); stopMotors(); if (bootLoader) { - systemResetToBootloader(); - return; + systemResetToBootloader(); + return; } systemReset(); } @@ -2749,10 +2749,10 @@ static void cliSet(char *cmdline) cliPrintf("%s = ", valueTable[i].name); cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui cliPrint("\r\n"); - + #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } } else if ((eqptr = strstr(cmdline, "=")) != NULL) { // has equals @@ -3082,22 +3082,22 @@ static void cliResource(char *cmdline) const char* owner; owner = ownerNames[ioRecs[i].owner]; - const char* resource; - resource = resourceNames[ioRecs[i].resource]; + const char* resource; + resource = resourceNames[ioRecs[i].resource]; - if (ioRecs[i].index > 0) { - cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource); - } else { - cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource); + if (ioRecs[i].index > 0) { + cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource); + } else { + cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource); } } } void cliDfu(char *cmdLine) { - UNUSED(cmdLine); - cliPrint("\r\nRestarting in DFU mode"); - cliRebootEx(true); + UNUSED(cmdLine); + cliPrint("\r\nRestarting in DFU mode"); + cliRebootEx(true); } void cliInit(serialConfig_t *serialConfig) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 4eb59402c8..e788401e77 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -293,7 +293,7 @@ static uint32_t read32(void) static void headSerialResponse(uint8_t err, uint8_t responseBodySize) { serialBeginWrite(mspSerialPort); - + serialize8('$'); serialize8('M'); serialize8(err ? '!' : '>'); diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index cfccf5c5d1..15a3de3347 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -76,7 +76,7 @@ static uint8_t locked = 0; void vtxInit(void) { - rtc6705Init(); + rtc6705Init(); if (masterConfig.vtx_mode == 0) { rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel); } else if (masterConfig.vtx_mode == 1) { diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index d49c2c7078..942a770547 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -17,11 +17,11 @@ #pragma once -#define VTX_BAND_MIN 1 -#define VTX_BAND_MAX 5 -#define VTX_CHANNEL_MIN 1 -#define VTX_CHANNEL_MAX 8 -#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 +#define VTX_BAND_MIN 1 +#define VTX_BAND_MAX 5 +#define VTX_CHANNEL_MIN 1 +#define VTX_CHANNEL_MAX 8 +#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 typedef struct vtxChannelActivationCondition_s { uint8_t auxChannelIndex; From 74679371aa499e7f6d15f499e683f0747e8ecdde Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 9 Jul 2016 13:34:28 +0100 Subject: [PATCH 082/108] Changed tabs to spaces in sensors/ --- src/main/sensors/barometer.c | 2 +- src/main/sensors/battery.c | 2 +- src/main/sensors/initialisation.c | 22 +++++++++++----------- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 1793e37948..ab3b9c5cf6 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -117,7 +117,7 @@ typedef enum { bool isBaroReady(void) { - return baroReady; + return baroReady; } uint32_t baroUpdate(void) diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 23159d87cd..84888e310b 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -213,7 +213,7 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea } fix12_t calculateVbatPidCompensation(void) { - fix12_t batteryScaler; + fix12_t batteryScaler; if (batteryConfig->vbatPidCompensation && feature(FEATURE_VBAT) && batteryCellCount > 1) { uint16_t maxCalculatedVoltage = batteryConfig->vbatmaxcellvoltage * batteryCellCount; batteryScaler = qConstruct(maxCalculatedVoltage, constrain(vbat, maxCalculatedVoltage - batteryConfig->vbatmaxcellvoltage, maxCalculatedVoltage)); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 0e75ad15f5..870959879b 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -418,20 +418,20 @@ static void detectBaro(baroSensor_e baroHardwareToUse) #ifdef USE_BARO_BMP085 - const bmp085Config_t *bmp085Config = NULL; + const bmp085Config_t *bmp085Config = NULL; #if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO) - static const bmp085Config_t defaultBMP085Config = { - .xclrIO = IO_TAG(BARO_XCLR_PIN), - .eocIO = IO_TAG(BARO_EOC_PIN), - }; - bmp085Config = &defaultBMP085Config; + static const bmp085Config_t defaultBMP085Config = { + .xclrIO = IO_TAG(BARO_XCLR_PIN), + .eocIO = IO_TAG(BARO_EOC_PIN), + }; + bmp085Config = &defaultBMP085Config; #endif #ifdef NAZE - if (hardwareRevision == NAZE32) { - bmp085Disable(bmp085Config); - } + if (hardwareRevision == NAZE32) { + bmp085Disable(bmp085Config); + } #endif #endif @@ -455,7 +455,7 @@ static void detectBaro(baroSensor_e baroHardwareToUse) break; } #endif - ; // fallthough + ; // fallthough case BARO_BMP280: #ifdef USE_BARO_BMP280 if (bmp280Detect(&baro)) { @@ -503,7 +503,7 @@ static void detectMag(magSensor_e magHardwareToUse) .intTag = IO_TAG(MAG_INT_EXTI) }; - hmc5883Config = &extiHmc5883Config; + hmc5883Config = &extiHmc5883Config; #endif #endif From ea283ab98cc2190e53cad021fc436b91b983a338 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 9 Jul 2016 14:39:39 +0100 Subject: [PATCH 083/108] Converted tabs to spaces --- src/main/blackbox/blackbox.c | 10 ++--- src/main/common/printf.c | 10 ++--- src/main/common/printf.h | 8 ++-- src/main/common/utils.h | 2 +- src/main/config/config.c | 16 +++---- src/main/drivers/accgyro_mpu.c | 6 +-- src/main/drivers/accgyro_spi_mpu6000.c | 4 +- src/main/drivers/accgyro_spi_mpu9250.c | 2 +- src/main/drivers/adc.c | 2 +- src/main/drivers/adc_impl.h | 4 +- src/main/drivers/adc_stm32f10x.c | 6 +-- src/main/drivers/adc_stm32f30x.c | 4 +- src/main/drivers/adc_stm32f4xx.c | 14 +++---- src/main/drivers/barometer_bmp085.c | 2 +- src/main/drivers/bus_i2c_soft.c | 6 +-- src/main/drivers/bus_i2c_stm32f10x.c | 42 +++++++++---------- src/main/drivers/bus_i2c_stm32f30x.c | 18 ++++---- src/main/drivers/bus_spi.c | 12 +++--- src/main/drivers/flash_m25p16.c | 6 +-- src/main/drivers/gpio.h | 4 +- src/main/drivers/inverter.c | 2 +- src/main/drivers/io_impl.h | 2 +- src/main/drivers/light_led.c | 38 ++++++++--------- .../drivers/light_ws2811strip_stm32f10x.c | 8 ++-- .../drivers/light_ws2811strip_stm32f30x.c | 8 ++-- .../drivers/light_ws2811strip_stm32f4xx.c | 34 +++++++-------- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/pwm_output.c | 6 +-- src/main/drivers/pwm_rx.c | 14 +++---- src/main/drivers/sdcard.c | 6 +-- src/main/drivers/serial_softserial.c | 14 +++---- src/main/drivers/serial_uart_stm32f10x.c | 20 ++++----- src/main/drivers/serial_uart_stm32f30x.c | 14 +++---- src/main/drivers/serial_uart_stm32f4xx.c | 28 ++++++------- src/main/drivers/serial_usb_vcp.c | 2 +- src/main/drivers/sonar_hcsr04.c | 4 +- src/main/drivers/system_stm32f10x.c | 6 +-- src/main/drivers/system_stm32f30x.c | 2 +- src/main/drivers/system_stm32f4xx.c | 24 +++++------ src/main/flight/gtune.c | 24 +++++------ src/main/flight/imu.c | 2 +- src/main/flight/mixer.c | 12 +++--- src/main/main.c | 16 +++---- src/main/rx/rx.c | 12 +++--- src/main/rx/spektrum.c | 2 +- src/main/rx/xbus.c | 16 +++---- src/main/scheduler/scheduler.c | 2 +- src/main/sensors/barometer.c | 4 +- src/main/sensors/battery.c | 4 +- src/main/sensors/initialisation.c | 4 +- src/main/target/BLUEJAYF4/target.h | 2 +- .../target/COLIBRI_RACE/bus_bst_stm32f30x.c | 2 +- src/main/target/DOGE/target.c | 2 +- src/main/target/FURYF3/target.c | 4 +- src/main/target/NAZE/hardware_revision.c | 2 +- src/main/target/system_stm32f30x.c | 40 +++++++++--------- src/main/target/system_stm32f4xx.h | 2 +- src/main/telemetry/smartport.c | 4 +- src/main/telemetry/telemetry.c | 2 +- src/main/vcpf4/usb_conf.h | 6 +-- src/main/vcpf4/usbd_cdc_vcp.c | 12 +++--- src/main/vcpf4/usbd_desc.c | 4 +- src/main/vcpf4/usbd_usr.c | 2 +- 63 files changed, 297 insertions(+), 297 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 46bae19584..c529f4132b 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -401,7 +401,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; - + case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI; @@ -638,7 +638,7 @@ static void writeInterframe(void) */ arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT); blackboxWriteTag2_3S32(deltas); - + /* * The PID D term is frequently set to zero for yaw, which makes the result from the calculation * always zero. So don't bother recording D results when PID D terms are zero. @@ -852,7 +852,7 @@ void startBlackbox(void) * cache those now. */ blackboxBuildConditionCache(); - + blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX); blackboxIteration = 0; @@ -1359,7 +1359,7 @@ static void blackboxLogIteration() } else { blackboxCheckAndLogArmingBeep(); blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event - + if (blackboxShouldLogPFrame(blackboxPFrameIndex)) { /* * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream. @@ -1496,7 +1496,7 @@ void handleBlackbox(void) blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume); blackboxSetState(BLACKBOX_STATE_RUNNING); - + blackboxLogIteration(); } diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 95e664a3cf..7847fb3035 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) putf(putp, ch); written++; } else { char lz = 0; -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT char lng = 0; #endif int w = 0; @@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) if (ch >= '0' && ch <= '9') { ch = a2i(ch, &fmt, 10, &w); } -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (ch == 'l') { ch = *(fmt++); lng = 1; @@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) case 0: goto abort; case 'u':{ -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) uli2a(va_arg(va, unsigned long int), 10, 0, bf); else @@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) break; } case 'd':{ -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) li2a(va_arg(va, unsigned long int), bf); else @@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) } case 'x': case 'X': -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf); else diff --git a/src/main/common/printf.h b/src/main/common/printf.h index e7606fbb94..dff4efdd2d 100644 --- a/src/main/common/printf.h +++ b/src/main/common/printf.h @@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function, something like : void putc ( void* p, char c) - { - while (!SERIAL_PORT_EMPTY) ; - SERIAL_PORT_TX_REGISTER = c; - } + { + while (!SERIAL_PORT_EMPTY) ; + SERIAL_PORT_TX_REGISTER = c; + } Before you can call printf you need to initialize it to use your character output function with something like: diff --git a/src/main/common/utils.h b/src/main/common/utils.h index db9e8c0c52..a5c0591918 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -56,7 +56,7 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html (32*((v)/2L>>31 > 0) \ + LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \ >>16*((v)/2L>>31 > 0))) - + #if 0 // ISO C version, but no type checking #define container_of(ptr, type, member) \ diff --git a/src/main/config/config.c b/src/main/config/config.c index 3d15e233e6..06ba7c9c09 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -538,7 +538,7 @@ static void resetConf(void) masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125; #endif masterConfig.servo_pwm_rate = 50; - + #ifdef CC3D masterConfig.use_buzzer_p6 = 0; #endif @@ -556,7 +556,7 @@ static void resetConf(void) masterConfig.emf_avoidance = 0; // TODO - needs removal resetPidProfile(¤tProfile->pidProfile); - + for (int rI = 0; rI MAX_RATEPROFILES) { - profileIndex = MAX_RATEPROFILES - 1; - } - setControlRateProfile(profileIndex); - activateControlRateConfig(); +{ + if (profileIndex > MAX_RATEPROFILES) { + profileIndex = MAX_RATEPROFILES - 1; + } + setControlRateProfile(profileIndex); + activateControlRateConfig(); } void latchActiveFeatures() diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index ca684aa6ea..9a3cd57253 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -165,7 +165,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(void) return true; } #endif - + return false; } #endif @@ -236,7 +236,7 @@ void mpuIntExtiInit(void) #if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); - + #ifdef ENSURE_MPU_DATA_READY_IS_LOW uint8_t status = IORead(mpuIntIO); if (status) { @@ -251,7 +251,7 @@ void mpuIntExtiInit(void) EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIEnable(mpuIntIO, true); #endif - + mpuExtiInitDone = true; } diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index b8c1360258..8c277dea5c 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -156,12 +156,12 @@ bool mpu6000SpiDetect(void) uint8_t in; uint8_t attemptsRemaining = 5; -#ifdef MPU6000_CS_PIN +#ifdef MPU6000_CS_PIN mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN)); #endif IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG); - + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET); diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 3e4d1635c8..219bd51a21 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -193,7 +193,7 @@ bool mpu9250SpiDetect(void) #endif IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); - + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index d214b49d35..a65abf9128 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -39,7 +39,7 @@ uint8_t adcChannelByTag(ioTag_t ioTag) if (ioTag == adcTagMap[i].tag) return adcTagMap[i].channel; } - return 0; + return 0; } uint16_t adcGetChannel(uint8_t channel) diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index ee2e92d40f..258c8acc8d 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -37,7 +37,7 @@ typedef enum ADCDevice { #elif defined(STM32F4) ADCDEV_2, ADCDEV_3, - ADCDEV_MAX = ADCDEV_3, + ADCDEV_MAX = ADCDEV_3, #else ADCDEV_MAX = ADCDEV_1, #endif @@ -47,7 +47,7 @@ typedef struct adcTagMap_s { ioTag_t tag; uint8_t channel; } adcTagMap_t; - + typedef struct adcDevice_s { ADC_TypeDef* ADCx; rccPeriphTag_t rccADC; diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index dc0598988f..451c9296c6 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -79,7 +79,7 @@ const adcTagMap_t adcTagMap[] = { void adcInit(drv_adc_config_t *init) { - + #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) UNUSED(init); #endif @@ -130,11 +130,11 @@ void adcInit(drv_adc_config_t *init) adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5; adcConfig[i].enabled = true; } - + RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE); - + DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index c9ae8dc47e..6297c2bd16 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -132,8 +132,8 @@ void adcInit(drv_adc_config_t *init) ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; - - adcDevice_t adc = adcHardware[device]; + + adcDevice_t adc = adcHardware[device]; for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index 4466f34430..e1bb1ae617 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -70,7 +70,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA4, ADC_Channel_4 }, { DEFIO_TAG_E__PA5, ADC_Channel_5 }, { DEFIO_TAG_E__PA6, ADC_Channel_6 }, - { DEFIO_TAG_E__PA7, ADC_Channel_7 }, + { DEFIO_TAG_E__PA7, ADC_Channel_7 }, }; ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) @@ -109,7 +109,7 @@ void adcInit(drv_adc_config_t *init) adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL; } #endif - + #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL; @@ -123,25 +123,25 @@ void adcInit(drv_adc_config_t *init) #endif //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - + ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; - + adcDevice_t adc = adcHardware[device]; - + for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; adcConfig[i].sampleTime = ADC_SampleTime_480Cycles; adcConfig[i].enabled = true; } - + RCC_ClockCmd(adc.rccDMA, ENABLE); RCC_ClockCmd(adc.rccADC, ENABLE); diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index ad4c547bf4..4c3e779855 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -367,7 +367,7 @@ static void bmp085_get_cal_param(void) bool bmp085TestEOCConnected(const bmp085Config_t *config) { UNUSED(config); - + if (!bmp085InitDone && eocIO) { bmp085_start_ut(); delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index cac5c62211..104c77c379 100644 --- a/src/main/drivers/bus_i2c_soft.c +++ b/src/main/drivers/bus_i2c_soft.c @@ -178,7 +178,7 @@ void i2cInit(I2CDevice device) bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data) { UNUSED(device); - + int i; if (!I2C_Start()) { i2cErrorCount++; @@ -206,7 +206,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, ui bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data) { UNUSED(device); - + if (!I2C_Start()) { return false; } @@ -227,7 +227,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data) bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf) { UNUSED(device); - + if (!I2C_Start()) { return false; } diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 14049461ae..281db6bf2d 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -133,7 +133,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device) bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) { - + if (device == I2CINVALID) return false; @@ -141,10 +141,10 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + state->addr = addr_ << 1; state->reg = reg_; state->writing = 1; @@ -182,12 +182,12 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t { if (device == I2CINVALID) return false; - + uint32_t timeout = I2C_DEFAULT_TIMEOUT; I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); @@ -220,13 +220,13 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t } static void i2c_er_handler(I2CDevice device) { - + I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + // Read the I2C1 status register volatile uint32_t SR1Register = I2Cx->SR1; @@ -255,13 +255,13 @@ static void i2c_er_handler(I2CDevice device) { } void i2c_ev_handler(I2CDevice device) { - + I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition static int8_t index; // index is signed -1 == send the subaddress uint8_t SReg_1 = I2Cx->SR1; // read the status register here @@ -384,17 +384,17 @@ void i2cInit(I2CDevice device) IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); - - IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); - IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); + + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(i2c->rcc, ENABLE); - + I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); - + i2cUnstick(scl, sda); - + // Init pins #ifdef STM32F4 IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); @@ -403,10 +403,10 @@ void i2cInit(I2CDevice device) IOConfigGPIO(scl, IOCFG_AF_OD); IOConfigGPIO(sda, IOCFG_AF_OD); #endif - + I2C_DeInit(i2c->dev); I2C_StructInit(&i2cInit); - + I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request i2cInit.I2C_Mode = I2C_Mode_I2C; i2cInit.I2C_DutyCycle = I2C_DutyCycle_2; @@ -424,8 +424,8 @@ void i2cInit(I2CDevice device) I2C_Init(i2c->dev, &i2cInit); I2C_StretchClockCmd(i2c->dev, ENABLE); - - + + // I2C ER Interrupt nvic.NVIC_IRQChannel = i2c->er_irq; nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER); diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 39cdb3b234..58d0caff31 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -79,23 +79,23 @@ uint32_t i2cTimeoutUserCallback(void) void i2cInit(I2CDevice device) { - + i2cDevice_t *i2c; i2c = &(i2cHardwareMap[device]); I2C_TypeDef *I2Cx; I2Cx = i2c->dev; - + IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); - + RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); - IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); - IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { @@ -107,11 +107,11 @@ void i2cInit(I2CDevice device) .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING) }; - + I2C_Init(I2Cx, &i2cInit); I2C_StretchClockCmd(I2Cx, ENABLE); - + I2C_Cmd(I2Cx, ENABLE); } @@ -126,7 +126,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { @@ -192,7 +192,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index b3b3f992bf..2eefe6edc6 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -114,9 +114,9 @@ void spiInitDevice(SPIDevice device) RCC_ResetCmd(spi->rcc, ENABLE); IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); - IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); - IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); - + IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); + IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); + #if defined(STM32F3) || defined(STM32F4) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); @@ -129,11 +129,11 @@ void spiInitDevice(SPIDevice device) IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); - + if (spi->nss) IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); #endif - + // Init SPI hardware SPI_I2S_DeInit(spi->dev); @@ -349,4 +349,4 @@ void spiResetErrorCounter(SPI_TypeDef *instance) SPIDevice device = spiDeviceByInstance(instance); if (device != SPIINVALID) spiHardwareMap[device].errorCount = 0; -} \ No newline at end of file +} diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index f4111e8259..c788dd8fe1 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -199,13 +199,13 @@ static bool m25p16_readIdentification() */ bool m25p16_init() { - -#ifdef M25P16_CS_PIN + +#ifdef M25P16_CS_PIN m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN)); #endif IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0); IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG); - + DISABLE_M25P16; #ifndef M25P16_SPI_SHARED diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h index 8f3a32a59a..dfa8d3761f 100644 --- a/src/main/drivers/gpio.h +++ b/src/main/drivers/gpio.h @@ -102,8 +102,8 @@ typedef struct #ifndef UNIT_TEST #ifdef STM32F4 -static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; } -static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; } +static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; } +static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; } #else static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; } static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; } diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index 0b31d5d8e6..fbbff6ffd4 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -33,7 +33,7 @@ void initInverter(void) { IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0); IOConfigGPIO(pin, IOCFG_OUT_PP); - + inverterSet(false); } diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index bed28dab33..1b3cca2bcf 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -13,7 +13,7 @@ typedef struct ioRec_s { uint16_t pin; resourceOwner_t owner; resourceType_t resource; - uint8_t index; + uint8_t index; } ioRec_t; extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 80582c1fa1..5fe73a1664 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -26,17 +26,17 @@ static const IO_t leds[] = { #ifdef LED0 DEFIO_IO(LED0), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #ifdef LED1 DEFIO_IO(LED1), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #ifdef LED2 DEFIO_IO(LED2), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) #ifdef LED0_A @@ -82,25 +82,25 @@ uint8_t ledOffset = 0; void ledInit(bool alternative_led) { - uint32_t i; + uint32_t i; #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) - if (alternative_led) - ledOffset = LED_NUMBER; + if (alternative_led) + ledOffset = LED_NUMBER; #else - UNUSED(alternative_led); + UNUSED(alternative_led); #endif - LED0_OFF; - LED1_OFF; - LED2_OFF; + LED0_OFF; + LED1_OFF; + LED2_OFF; - for (i = 0; i < LED_NUMBER; i++) { - if (leds[i + ledOffset]) { - IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); - IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); - } - } + for (i = 0; i < LED_NUMBER; i++) { + if (leds[i + ledOffset]) { + IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); + IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); + } + } LED0_OFF; LED1_OFF; @@ -109,11 +109,11 @@ void ledInit(bool alternative_led) void ledToggle(int led) { - IOToggle(leds[led + ledOffset]); + IOToggle(leds[led + ledOffset]); } void ledSet(int led, bool on) { - bool inverted = (1 << (led + ledOffset)) & ledPolarity; - IOWrite(leds[led + ledOffset], on ? inverted : !inverted); + bool inverted = (1 << (led + ledOffset)) & ledPolarity; + IOWrite(leds[led + ledOffset], on ? inverted : !inverted); } diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 863dd24ea0..63c76baec4 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -50,14 +50,14 @@ void ws2811LedStripHardwareInit(void) uint16_t prescalerValue; dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); - + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); - + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); - + /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ @@ -123,7 +123,7 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(TIM3, 0); TIM_Cmd(TIM3, ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index b27e30e51e..782be0a98d 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -59,14 +59,14 @@ void ws2811LedStripHardwareInit(void) DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; - + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); - + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); - + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); /* Compute the prescaler value */ @@ -134,7 +134,7 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(WS2811_TIMER, 0); TIM_Cmd(WS2811_TIMER, ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index cfde3411c4..1b4c646a45 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -69,15 +69,15 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); + IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); - + // Stop timer TIM_Cmd(WS2811_TIMER, DISABLE); /* Compute the prescaler value */ prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1; - + /* Time base configuration */ TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; @@ -94,7 +94,7 @@ void ws2811LedStripHardwareInit(void) TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; TIM_OCInitStructure.TIM_Pulse = 0; - + uint32_t channelAddress = 0; switch (WS2811_TIMER_CHANNEL) { case TIM_Channel_1: @@ -102,28 +102,28 @@ void ws2811LedStripHardwareInit(void) timDMASource = TIM_DMA_CC1; channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_2: TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC2; channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_3: TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC3; channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_4: TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC4; channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; } - - TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); + + TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE); TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable); @@ -132,7 +132,7 @@ void ws2811LedStripHardwareInit(void) dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); /* configure DMA */ - DMA_Cmd(WS2811_DMA_STREAM, DISABLE); + DMA_Cmd(WS2811_DMA_STREAM, DISABLE); DMA_DeInit(WS2811_DMA_STREAM); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL; @@ -151,13 +151,13 @@ void ws2811LedStripHardwareInit(void) DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; - - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); + + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure); DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE); - DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); - + DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); + NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ; @@ -175,11 +175,11 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(WS2811_TIMER, 0); DMA_Cmd(WS2811_DMA_STREAM, ENABLE); TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE); } -#endif \ No newline at end of file +#endif diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 2636b61353..80d2b01d92 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -101,7 +101,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) int channelIndex = 0; memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration)); - + // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] if (init->airplane) i = 2; // switch to air hardware config diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index f9feb1a469..d75ff21c57 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -90,9 +90,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 configTimeBase(timerHardware->tim, period, mhz); - IO_t io = IOGetByTag(timerHardware->tag); - IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); - IOConfigGPIO(io, IOCFG_AF_PP); + IO_t io = IOGetByTag(timerHardware->tag); + IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); + IOConfigGPIO(io, IOCFG_AF_PP); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 7250c6e795..a0f65f4e3a 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -366,9 +366,9 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - IO_t io = IOGetByTag(timerHardwarePtr->tag); - IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); - IOConfigGPIO(io, timerHardwarePtr->ioMode); + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); + IOConfigGPIO(io, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); @@ -398,10 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - IO_t io = IOGetByTag(timerHardwarePtr->tag); - IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); - IOConfigGPIO(io, timerHardwarePtr->ioMode); - + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); + IOConfigGPIO(io, timerHardwarePtr->ioMode); + pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index 852c4adcf2..722715fc16 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -550,7 +550,7 @@ void sdcard_init(bool useDMA) IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0); IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG); #endif // SDCARD_SPI_CS_PIN - + // Max frequency is initially 400kHz spiSetDivisor(SDCARD_SPI_INSTANCE, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER); @@ -559,7 +559,7 @@ void sdcard_init(bool useDMA) // Transmit at least 74 dummy clock cycles with CS high so the SD card can start up SET_CS_HIGH; - + spiTransfer(SDCARD_SPI_INSTANCE, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES); // Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles: @@ -1059,7 +1059,7 @@ bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationComp sdcard.pendingOperation.blockIndex = blockIndex; sdcard.pendingOperation.callback = callback; sdcard.pendingOperation.callbackData = callbackData; - + sdcard.state = SDCARD_STATE_READING; sdcard.operationStartTime = millis(); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 082fddf9c6..e44ff10a33 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -102,18 +102,18 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) void serialInputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); #ifdef STM32F1 - IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); + IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); #else - IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); + IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); #endif } static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); - IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); + IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); } static bool isTimerPeriodTooLarge(uint32_t timerPeriod) @@ -216,9 +216,9 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex); - + softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); - serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); + serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); setTxSignal(softSerial, ENABLE); delay(50); diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 8e73277fcd..0a8515dc88 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -88,14 +88,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort1; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = rx1Buffer; s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; - + s->USARTx = USART1; @@ -179,14 +179,14 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort2; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; - + s->USARTx = USART2; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; @@ -207,7 +207,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); + IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } @@ -260,16 +260,16 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB1(USART3), ENABLE); if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); } } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index a7a3f004bf..ae7516979c 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -120,7 +120,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui } if (mode & MODE_RX) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(rx, ioCfg, af); } } @@ -136,14 +136,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort1; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = rx1Buffer; s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; - + #ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; #endif @@ -188,16 +188,16 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort2; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; s->USARTx = USART2; - + #ifdef USE_UART2_RX_DMA s->rxDMAChannel = DMA1_Channel6; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 40f7a919ea..d689426215 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -277,17 +277,17 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po uartDevice_t *uart = uartHardwareMap[device]; if (!uart) return NULL; - + s = &(uart->port); s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = uart->rxBuffer; s->port.txBuffer = uart->txBuffer; s->port.rxBufferSize = sizeof(uart->rxBuffer); s->port.txBufferSize = sizeof(uart->txBuffer); - + s->USARTx = uart->dev; if (uart->rxDMAStream) { s->rxDMAChannel = uart->DMAChannel; @@ -295,34 +295,34 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po } s->txDMAChannel = uart->DMAChannel; s->txDMAStream = uart->txDMAStream; - + s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - + IO_t tx = IOGetByTag(uart->tx); IO_t rx = IOGetByTag(uart->rx); - + if (uart->rcc_apb2) RCC_ClockCmd(uart->rcc_apb2, ENABLE); - + if (uart->rcc_apb1) RCC_ClockCmd(uart->rcc_apb1, ENABLE); - + if (uart->rcc_ahb1) RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE); - + if (options & SERIAL_BIDIR) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); } else { if (mode & MODE_TX) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); } - + if (mode & MODE_RX) { - IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); + IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } } diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index f489b16d30..5f1b223918 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -117,7 +117,7 @@ static bool usbVcpFlush(vcpPort_t *port) if (count == 0) { return true; } - + if (!usbIsConnected() || !usbIsConfigured()) { return false; } diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 0cf058a8a2..cbfcf80a1a 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -85,10 +85,10 @@ void hcsr04_init(sonarRange_t *sonarRange) triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); - + // echo pin echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); - IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); + IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); #ifdef USE_EXTI diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index 3e59fe7342..c273c6f3dc 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -69,10 +69,10 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); SetSysClock(false); - + #ifdef CC3D /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ extern void *isr_vector_table_base; @@ -115,4 +115,4 @@ void systemInit(void) void checkForBootLoaderRequest(void) { -} \ No newline at end of file +} diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index ee8aef1a0e..d762e2c333 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -83,7 +83,7 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); // Enable FPU SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2)); diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 53f3767a5e..e7587aa9b3 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -169,7 +169,7 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); SetSysClock(); @@ -183,7 +183,7 @@ void systemInit(void) extern void *isr_vector_table_base; NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); - + RCC_ClearFlag(); enableGPIOPowerUsageAndNoiseReductions(); @@ -199,15 +199,15 @@ void systemInit(void) void(*bootJump)(void); void checkForBootLoaderRequest(void) { - if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { + if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { - *((uint32_t *)0x2001FFFC) = 0x0; + *((uint32_t *)0x2001FFFC) = 0x0; - __enable_irq(); - __set_MSP(0x20001000); - - bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); - bootJump(); - while (1); - } -} \ No newline at end of file + __enable_irq(); + __set_MSP(0x20001000); + + bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); + bootJump(); + while (1); + } +} diff --git a/src/main/flight/gtune.c b/src/main/flight/gtune.c index d32a93ad8d..afef499d59 100644 --- a/src/main/flight/gtune.c +++ b/src/main/flight/gtune.c @@ -52,12 +52,12 @@ extern uint8_t motorCount; **************************************************************************** *** G_Tune *** **************************************************************************** - G_Tune Mode - This is the multiwii implementation of ZERO-PID Algorithm - http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html - The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) + G_Tune Mode + This is the multiwii implementation of ZERO-PID Algorithm + http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html + The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) - You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. + You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. */ /* @@ -107,13 +107,13 @@ void init_Gtune(pidProfile_t *pidProfileToTune) uint8_t i; pidProfile = pidProfileToTune; - if (pidProfile->pidController == 2) { - floatPID = true; // LuxFloat is using float values for PID settings - } else { - floatPID = false; - } - updateDelayCycles(); - for (i = 0; i < 3; i++) { + if (pidProfile->pidController == 2) { + floatPID = true; // LuxFloat is using float values for PID settings + } else { + floatPID = false; + } + updateDelayCycles(); + for (i = 0; i < 3; i++) { if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter } diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index d885d30eaa..8945e765e6 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -84,7 +84,7 @@ STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) float q1q1 = sq(q1); float q2q2 = sq(q2); float q3q3 = sq(q3); - + float q0q1 = q0 * q1; float q0q2 = q0 * q2; float q0q3 = q0 * q3; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b5da4a0170..fbde38a3f8 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -395,7 +395,7 @@ void loadCustomServoMixer(void) // check if done if (customServoMixers[i].rate == 0) break; - + currentServoMixer[i] = customServoMixers[i]; servoRuleCount++; } @@ -426,9 +426,9 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura motorCount = 0; servoCount = pwmOutputConfiguration->servoCount; - + syncPwm = use_unsyncedPwm; - + if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) { // load custom mixer into currentMixer for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) { @@ -454,7 +454,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura currentServoMixer[i] = servoMixers[currentMixerMode].rule[i]; } } - + // in 3D mode, mixer gain has to be halved if (feature(FEATURE_3D)) { if (motorCount > 1) { @@ -472,7 +472,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura currentMixerMode == MIXER_CUSTOM_AIRPLANE ) { ENABLE_STATE(FIXED_WING); - + if (currentMixerMode == MIXER_CUSTOM_AIRPLANE) { loadCustomServoMixer(); } @@ -901,7 +901,7 @@ void mixTable(void) /* case MIXER_GIMBAL: - servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); + servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); break; */ diff --git a/src/main/main.c b/src/main/main.c index 455d4b2606..01865fdbf7 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -166,8 +166,8 @@ void init(void) //i2cSetOverclock(masterConfig.i2c_overclock); // initialize IO (needed for all IO operations) - IOInitGlobal(); - + IOInitGlobal(); + debugMode = masterConfig.debug_mode; #ifdef USE_HARDWARE_REVISION_DETECTION @@ -188,7 +188,7 @@ void init(void) ledInit(false); #endif LED2_ON; - + #ifdef USE_EXTI EXTIInit(); #endif @@ -286,7 +286,7 @@ void init(void) #endif #if defined(USE_UART6) && defined(STM32F40_41xxx) pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6); -#endif +#endif pwm_params.useVbat = feature(FEATURE_VBAT); pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM); @@ -309,7 +309,7 @@ void init(void) } else { featureClear(FEATURE_ONESHOT125); } - + bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; // Configurator feature abused for enabling Fast PWM @@ -319,7 +319,7 @@ void init(void) pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; - + if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) { featureClear(FEATURE_3D); pwm_params.idlePulse = 0; // brushed motors @@ -363,7 +363,7 @@ void init(void) #endif #ifdef CC3D if (masterConfig.use_buzzer_p6 == 1) - beeperConfig.ioTag = IO_TAG(BEEPER_OPT); + beeperConfig.ioTag = IO_TAG(BEEPER_OPT); #endif beeperInit(&beeperConfig); @@ -501,7 +501,7 @@ void init(void) LED1_ON; LED0_OFF; LED2_OFF; - + for (int i = 0; i < 10; i++) { LED1_TOGGLE; LED0_TOGGLE; diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 255fb547ea..50fe4f4578 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -590,12 +590,12 @@ void updateRSSIPWM(void) int16_t pwmRssi = 0; // Read value of AUX channel as rssi pwmRssi = rcData[rxConfig->rssi_channel - 1]; - - // RSSI_Invert option - if (rxConfig->rssi_ppm_invert) { - pwmRssi = ((2000 - pwmRssi) + 1000); - } - + + // RSSI_Invert option + if (rxConfig->rssi_ppm_invert) { + pwmRssi = ((2000 - pwmRssi) + 1000); + } + // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023]; rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f); } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index ef6a8fa3dc..fb211bfcf7 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -245,7 +245,7 @@ void spektrumBind(rxConfig_t *rxConfig) #ifndef HARDWARE_BIND_PLUG // If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config // Don't reset if hardware bind plug is present - // Reset only when autoreset is enabled + // Reset only when autoreset is enabled if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { rxConfig->spektrum_sat_bind = 0; saveConfigAndNotify(); diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index ba70eb579b..0e68854897 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -71,7 +71,7 @@ // 2200µs -> 0xFFF // Total range is: 2200 - 800 = 1400 <==> 4095 // Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12) -#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12)) +#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12)) static bool xBusFrameReceived = false; static bool xBusDataIncoming = false; @@ -148,7 +148,7 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa static uint16_t xBusCRC16(uint16_t crc, uint8_t value) { uint8_t i; - + crc = crc ^ (int16_t)value << 8; for (i = 0; i < 8; i++) { @@ -181,7 +181,7 @@ uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed) inData >>= 1; } - return seed; + return seed; } @@ -240,7 +240,7 @@ static void xBusUnpackRJ01Frame(void) // method. // So, we check both these values as well as the provided length // of the outer/full message (LEN) - + // // Check we have correct length of message // @@ -249,14 +249,14 @@ static void xBusUnpackRJ01Frame(void) // Unknown package as length is not ok return; } - + // // CRC calculation & check for full message // for (i = 0; i < xBusFrameLength - 1; i++) { outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]); } - + if (outerCrc != xBusFrame[xBusFrameLength - 1]) { // CRC does not match, skip this frame @@ -281,7 +281,7 @@ static void xBusDataReceive(uint16_t c) xBusFramePosition = 0; xBusDataIncoming = false; } - + // Check if we shall start a frame? if ((xBusFramePosition == 0) && (c == XBUS_START_OF_FRAME_BYTE)) { xBusDataIncoming = true; @@ -293,7 +293,7 @@ static void xBusDataReceive(uint16_t c) xBusFrame[xBusFramePosition] = (uint8_t)c; xBusFramePosition++; } - + // Done? if (xBusFramePosition == xBusFrameLength) { switch (xBusProvider) { diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index 7fe3fea8ec..cff97d77e4 100755 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -139,7 +139,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros) { if (taskId == TASK_SELF || taskId < TASK_COUNT) { cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId]; - task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging + task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging } } diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index ab3b9c5cf6..2d7b44e551 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -68,7 +68,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading) static int currentFilterSampleIndex = 0; static bool medianFilterReady = false; int nextSampleIndex; - + nextSampleIndex = (currentFilterSampleIndex + 1); if (nextSampleIndex == PRESSURE_SAMPLES_MEDIAN) { nextSampleIndex = 0; @@ -77,7 +77,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading) barometerFilterSamples[currentFilterSampleIndex] = newPressureReading; currentFilterSampleIndex = nextSampleIndex; - + if (medianFilterReady) return quickMedianFilter3(barometerFilterSamples); else diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 84888e310b..c6e3be93ca 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -86,7 +86,7 @@ static void updateBatteryVoltage(void) void updateBattery(void) { updateBatteryVoltage(); - + /* battery has just been connected*/ if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD_MV) { @@ -115,7 +115,7 @@ void updateBattery(void) batteryCellCount = 0; batteryWarningVoltage = 0; batteryCriticalVoltage = 0; - } + } switch(batteryState) { diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 870959879b..eb206627b4 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -93,7 +93,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) return selectMPUIntExtiConfigByHardwareRevision(); #else return NULL; -#endif +#endif } #ifdef USE_FAKE_GYRO @@ -233,7 +233,7 @@ bool detectGyro(void) } #endif ; // fallthrough - + case GYRO_MPU9250: #ifdef USE_GYRO_SPI_MPU9250 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 4d3b7a58a9..e83499615a 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -94,7 +94,7 @@ #define USE_VCP //#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_ENABLED - + #define USE_UART1 #define UART1_RX_PIN PA10 #define UART1_TX_PIN PA9 diff --git a/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c index f23932a6e6..655f19cfe6 100644 --- a/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c +++ b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c @@ -237,7 +237,7 @@ void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/) NVIC_Init(&nvic); I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); - + I2C_Cmd(I2C1, ENABLE); } diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index c07a925414..c813ceecba 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -78,7 +78,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8 { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9 - + { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10 { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9 { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index e52da0ab27..21b05ab5d4 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -23,7 +23,7 @@ const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -46,7 +46,7 @@ const uint16_t multiPWM[] = { const uint16_t airPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_SERVO_OUTPUT << 8), diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index d71edde627..3f87237dbb 100755 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -70,7 +70,7 @@ uint8_t detectSpiDevice(void) #ifdef NAZE_SPI_CS_PIN nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); #endif - + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; uint8_t in[4]; uint32_t flash_id; diff --git a/src/main/target/system_stm32f30x.c b/src/main/target/system_stm32f30x.c index 78274ac322..09ba3fa47c 100644 --- a/src/main/target/system_stm32f30x.c +++ b/src/main/target/system_stm32f30x.c @@ -8,7 +8,7 @@ * This file contains the system clock configuration for STM32F30x devices, * and is generated by the clock configuration tool * stm32f30x_Clock_Configuration_V1.0.0.xls - * + * * 1. This file provides two functions and one global variable to be called from * user application: * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier @@ -21,7 +21,7 @@ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used * by the user application to setup the SysTick * timer or configure other parameters. - * + * * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must * be called whenever the core clock is changed * during program execution. @@ -41,7 +41,7 @@ * * 5. This file configures the system clock as follows: *============================================================================= - * Supported STM32F30x device + * Supported STM32F30x device *----------------------------------------------------------------------------- * System Clock source | PLL (HSE) *----------------------------------------------------------------------------- @@ -204,34 +204,34 @@ void SystemInit(void) * The SystemCoreClock variable contains the core clock (HCLK), it can * be used by the user application to setup the SysTick timer or configure * other parameters. - * + * * @note Each time the core clock (HCLK) changes, this function must be called * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * + * based on this variable will be incorrect. + * * @note - The system frequency computed by this function is not the real * frequency in the chip. It is calculated based on the predefined * constant and the selected clock source: - * + * * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * + * * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * + * * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * + * * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz) but the real value may vary depending on the variations * in voltage and temperature. - * + * * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz), user has to ensure that HSE_VALUE is same as the real * frequency of the crystal used. Otherwise, this function may * have wrong result. - * + * * - The result of this function could be not correct when using fractional * value for HSE crystal. - * + * * @param None * @retval None */ @@ -255,7 +255,7 @@ void SystemCoreClockUpdate (void) pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; pllmull = ( pllmull >> 18) + 2; - + if (pllsource == 0x00) { /* HSI oscillator clock divided by 2 selected as PLL clock entry */ @@ -266,7 +266,7 @@ void SystemCoreClockUpdate (void) prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; /* HSE oscillator clock selected as PREDIV1 clock entry */ SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; - } + } break; default: /* HSI used as system clock */ SystemCoreClock = HSI_VALUE; @@ -282,8 +282,8 @@ void SystemCoreClockUpdate (void) /** * @brief Configures the System clock source, PLL Multiplier and Divider factors, * AHB/APBx prescalers and Flash settings - * @note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). * @param None * @retval None */ @@ -322,10 +322,10 @@ void SetSysClock(void) /* HCLK = SYSCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - + /* PCLK2 = HCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - + /* PCLK1 = HCLK / 2 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; @@ -340,7 +340,7 @@ void SetSysClock(void) while((RCC->CR & RCC_CR_PLLRDY) == 0) { } - + /* Select PLL as system clock source */ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; diff --git a/src/main/target/system_stm32f4xx.h b/src/main/target/system_stm32f4xx.h index 6d130d8512..e266366801 100644 --- a/src/main/target/system_stm32f4xx.h +++ b/src/main/target/system_stm32f4xx.h @@ -4,7 +4,7 @@ * @author MCD Application Team * @version V1.6.1 * @date 21-October-2015 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. + * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. ****************************************************************************** * @attention * diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 36b7c95569..28daadc40b 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -279,7 +279,7 @@ void checkSmartPortTelemetryState(void) void handleSmartPortTelemetry(void) { uint32_t smartPortLastServiceTime = millis(); - + if (!smartPortTelemetryEnabled) { return; } @@ -307,7 +307,7 @@ void handleSmartPortTelemetry(void) smartPortHasRequest = 0; return; } - + // we can send back any data we want, our table keeps track of the order and frequency of each data type we send uint16_t id = frSkyDataIdTable[smartPortIdCnt]; if (id == 0) { // end of table reached, loop back diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index f4f38ba947..e3871aead0 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -56,7 +56,7 @@ void telemetryInit(void) initSmartPortTelemetry(telemetryConfig); initLtmTelemetry(telemetryConfig); initJetiExBusTelemetry(telemetryConfig); - + telemetryCheckState(); } diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h index 60c8036202..ea8d49bcf1 100644 --- a/src/main/vcpf4/usb_conf.h +++ b/src/main/vcpf4/usb_conf.h @@ -207,12 +207,12 @@ /****************** C Compilers dependant keywords ****************************/ /* In HS mode and when the DMA is used, all variables and data structures dealing - with the DMA during the transaction process should be 4-bytes aligned */ + with the DMA during the transaction process should be 4-bytes aligned */ #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined (__GNUC__) /* GNU Compiler */ #define __ALIGN_END __attribute__ ((aligned (4))) - #define __ALIGN_BEGIN - #else + #define __ALIGN_BEGIN + #else #define __ALIGN_END #if defined (__CC_ARM) /* ARM Compiler */ #define __ALIGN_BEGIN __align(4) diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 8b789fa48f..5672eeae55 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -111,23 +111,23 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) break; // Not needed for this driver - case SET_COMM_FEATURE: + case SET_COMM_FEATURE: case GET_COMM_FEATURE: case CLEAR_COMM_FEATURE: break; - + //Note - hw flow control on UART 1-3 and 6 only case SET_LINE_CODING: ust_cpy(&g_lc, plc); //Copy into structure to save for later break; - - + + case GET_LINE_CODING: ust_cpy(plc, &g_lc); break; - + case SET_CONTROL_LINE_STATE: /* Not needed for this driver */ //RSW - This tells how to set RTS and DTR @@ -234,7 +234,7 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; - + return USBD_OK; } diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index f3f9a3af91..ab1a3e1d35 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -166,8 +166,8 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI /* USB Standard Device Descriptor */ __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = { - USB_SIZ_STRING_LANGID, - USB_DESC_TYPE_STRING, + USB_SIZ_STRING_LANGID, + USB_DESC_TYPE_STRING, LOBYTE(USBD_LANGID_STRING), HIBYTE(USBD_LANGID_STRING), }; diff --git a/src/main/vcpf4/usbd_usr.c b/src/main/vcpf4/usbd_usr.c index 395400d29f..958e772322 100644 --- a/src/main/vcpf4/usbd_usr.c +++ b/src/main/vcpf4/usbd_usr.c @@ -63,7 +63,7 @@ void USBD_USR_DeviceReset(uint8_t speed ) break; default: break; - + } } From 2b7b70c520ff3dfb413615c5a7e02ba0dbe25802 Mon Sep 17 00:00:00 2001 From: TheAngularity Date: Sat, 9 Jul 2016 16:26:46 +0200 Subject: [PATCH 084/108] Update atomic.h Bump version check number - Version for warning is increased to gcc > 5.x --- src/main/common/atomic.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/common/atomic.h b/src/main/common/atomic.h index 9473c85a0e..b2aea26282 100644 --- a/src/main/common/atomic.h +++ b/src/main/common/atomic.h @@ -85,7 +85,7 @@ static inline uint8_t __basepriSetRetVal(uint8_t prio) // ideally this would only protect memory passed as parameter (any type should work), but gcc is curently creating almost full barrier // this macro can be used only ONCE PER LINE, but multiple uses per block are fine -#if (__GNUC__ > 4) +#if (__GNUC__ > 5) #warning "Please verify that ATOMIC_BARRIER works as intended" // increment version number is BARRIER works // TODO - use flag to disable ATOMIC_BARRIER and use full barrier instead From 26609a462350a86728962fb1e3922ac965475a58 Mon Sep 17 00:00:00 2001 From: Moto Moto Date: Sat, 9 Jul 2016 13:06:12 -0500 Subject: [PATCH 085/108] Defined I2C_SCL and I2C_SDA for MOTOLAB --- src/main/target/MOTOLAB/target.h | 15 +++------------ 1 file changed, 3 insertions(+), 12 deletions(-) diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 183e1326d5..79b8d6f495 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -90,18 +90,9 @@ #define UART3_RX_PINSOURCE GPIO_PinSource11 #define USE_I2C -#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) - -#define I2C2_SCL_GPIO GPIOA -#define I2C2_SCL_GPIO_AF GPIO_AF_4 -#define I2C2_SCL_PIN PA9 -#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 -#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA -#define I2C2_SDA_GPIO GPIOA -#define I2C2_SDA_GPIO_AF GPIO_AF_4 -#define I2C2_SDA_PIN PA10 -#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 -#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA +#define I2C_DEVICE (I2CDEV_2) +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 #define USE_SPI #define USE_SPI_DEVICE_2 From 68026f7c3ea403c82f3d9f0e4de0596144228ef1 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sat, 9 Jul 2016 17:51:19 +1000 Subject: [PATCH 086/108] fix PWM remaining active on soft reset. --- src/main/flight/mixer.c | 3 ++- src/main/flight/mixer.h | 2 +- src/main/io/serial_cli.c | 2 +- src/main/io/serial_msp.c | 2 +- src/main/main.c | 6 ------ 5 files changed, 5 insertions(+), 10 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index fbde38a3f8..cd2a0272cd 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -666,9 +666,10 @@ void stopMotors(void) delay(50); // give the timers and ESCs a chance to react. } -void StopPwmAllMotors() +void stopPwmAllMotors() { pwmShutdownPulsesForAllMotors(motorCount); + delayMicroseconds(1500); } #ifndef USE_QUAD_MIXER_ONLY diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index f3999517c7..4f4869b205 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -215,4 +215,4 @@ void mixTable(void); void syncMotors(bool enabled); void writeMotors(void); void stopMotors(void); -void StopPwmAllMotors(void); +void stopPwmAllMotors(void); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 8f8bad45d9..49219a129e 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2574,7 +2574,7 @@ static void cliRebootEx(bool bootLoader) cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); - stopMotors(); + stopPwmAllMotors(); if (bootLoader) { systemResetToBootloader(); return; diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index e788401e77..48d6ae92e8 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1967,7 +1967,7 @@ void mspProcess(void) if (isRebootScheduled) { waitForSerialPortToFinishTransmitting(candidatePort->port); - stopMotors(); + stopPwmAllMotors(); // On real flight controllers, systemReset() will do a soft reset of the device, // reloading the program. But to support offline testing this flag needs to be // cleared so that the software doesn't continuously attempt to reboot itself. diff --git a/src/main/main.c b/src/main/main.c index 01865fdbf7..a411117617 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -335,12 +335,6 @@ void init(void) mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); -/* - // TODO is this needed here? enables at the end - if (!feature(FEATURE_ONESHOT125)) - motorControlEnable = true; - -*/ systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef BEEPER From 35ad4c493882d86af4878ffd42ae01e8f4fce327 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 10 Jul 2016 07:50:00 +1000 Subject: [PATCH 087/108] tabs to spaces --- src/main/flight/mixer.c | 2 +- src/main/io/serial_cli.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index cd2a0272cd..b851fd355e 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -669,7 +669,7 @@ void stopMotors(void) void stopPwmAllMotors() { pwmShutdownPulsesForAllMotors(motorCount); - delayMicroseconds(1500); + delayMicroseconds(1500); } #ifndef USE_QUAD_MIXER_ONLY diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 49219a129e..c0f3a8c417 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -2574,7 +2574,7 @@ static void cliRebootEx(bool bootLoader) cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); - stopPwmAllMotors(); + stopPwmAllMotors(); if (bootLoader) { systemResetToBootloader(); return; From 95a22053d71b6f68e15d0a77ce22e1c7e822c7a1 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Sat, 9 Jul 2016 20:28:18 -0700 Subject: [PATCH 088/108] avoid warnings --- src/main/drivers/serial_uart_stm32f10x.c | 2 +- src/main/drivers/serial_uart_stm32f30x.c | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 4cf886d075..330b3f837a 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -139,7 +139,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option } // DMA TX Interrupt - dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1); + dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1); #ifndef USE_UART1_RX_DMA // RX/TX Interrupt diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index f586ee5276..ee65d54d2d 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -171,7 +171,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1); - dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1); + dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1); #ifndef USE_UART1_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; @@ -225,7 +225,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option #ifdef USE_UART2_TX_DMA // DMA TX Interrupt - dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, &uartPort2); + dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, (uint32_t)&uartPort2); #endif #ifndef USE_UART2_RX_DMA @@ -280,7 +280,7 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option #ifdef USE_UART3_TX_DMA // DMA TX Interrupt - dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, &uartPort3); + dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, (uint32_t)&uartPort3); #endif #ifndef USE_UART3_RX_DMA From acee56764bfff8757f9c8e8d4073e2719657c248 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sun, 10 Jul 2016 08:03:22 +0100 Subject: [PATCH 089/108] Fixed accelerometer scaling in MSP --- src/main/io/serial_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index e788401e77..375827d512 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -766,7 +766,7 @@ static bool processOutCommand(uint8_t cmdMSP) headSerialReply(18); // Hack scale due to choice of units for sensor data in multiwii - uint8_t scale = (acc.acc_1G > 1024) ? 8 : 1; + const uint8_t scale = (acc.acc_1G > 512) ? 4 : 1; for (i = 0; i < 3; i++) serialize16(accSmooth[i] / scale); From 085e88cfd92a3d33e50632659b73763baa44d94c Mon Sep 17 00:00:00 2001 From: Sami Korhonen Date: Sun, 10 Jul 2016 11:21:32 +0300 Subject: [PATCH 090/108] Fix F4 timers + fix pwm output generation --- src/main/drivers/light_ws2811strip.h | 5 +++ src/main/drivers/pwm_mapping.h | 10 ++++++ src/main/drivers/pwm_output.c | 16 +++++++-- src/main/drivers/timer.c | 54 ++++++++++++++++++++++++++++ 4 files changed, 83 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/light_ws2811strip.h b/src/main/drivers/light_ws2811strip.h index 88282ca593..974c19c655 100644 --- a/src/main/drivers/light_ws2811strip.h +++ b/src/main/drivers/light_ws2811strip.h @@ -25,8 +25,13 @@ #define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH) // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes) +#if defined(STM32F40_41xxx) +#define BIT_COMPARE_1 67 // timer compare value for logical 1 +#define BIT_COMPARE_0 33 // timer compare value for logical 0 +#else #define BIT_COMPARE_1 17 // timer compare value for logical 1 #define BIT_COMPARE_0 9 // timer compare value for logical 0 +#endif void ws2811LedStripInit(void); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 40aa5d4d2a..ffb5540995 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -34,10 +34,20 @@ #define MAX_INPUTS 8 #define PWM_TIMER_MHZ 1 +#if defined(STM32F40_41xxx) // must be multiples of timer clock +#define ONESHOT42_TIMER_MHZ 21 +#define ONESHOT125_TIMER_MHZ 12 +#define PWM_BRUSHED_TIMER_MHZ 21 +#define MULTISHOT_TIMER_MHZ 84 +#else #define PWM_BRUSHED_TIMER_MHZ 24 #define MULTISHOT_TIMER_MHZ 72 #define ONESHOT42_TIMER_MHZ 24 #define ONESHOT125_TIMER_MHZ 8 +#endif + +#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5) +#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f) typedef struct sonarIOConfig_s { ioTag_t triggerTag; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index d75ff21c57..fd8446584d 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -131,9 +131,19 @@ static void pwmWriteStandard(uint8_t index, uint16_t value) *motors[index]->ccr = value; } +static void pwmWriteOneShot42(uint8_t index, uint16_t value) +{ + *motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f)); +} + +static void pwmWriteOneShot125(uint8_t index, uint16_t value) +{ + *motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f)); +} + static void pwmWriteMultiShot(uint8_t index, uint16_t value) { - *motors[index]->ccr = lrintf(((float)(value-1000) / 0.69444f) + 360); + *motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW); } void pwmWriteMotor(uint8_t index, uint16_t value) @@ -218,7 +228,9 @@ void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIn motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0); } - motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot : pwmWriteStandard; + motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot : + ((fastPwmProtocolType == PWM_TYPE_ONESHOT125) ? pwmWriteOneShot125 : + pwmWriteOneShot42); } #ifdef USE_SERVOS diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 7938b9a5be..a3b3624371 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -88,9 +88,36 @@ static uint8_t lookupTimerIndex(const TIM_TypeDef *tim) #if USED_TIMERS & TIM_N(4) _CASE(4); #endif +#if USED_TIMERS & TIM_N(5) + _CASE(5); +#endif +#if USED_TIMERS & TIM_N(6) + _CASE(6); +#endif +#if USED_TIMERS & TIM_N(7) + _CASE(7); +#endif #if USED_TIMERS & TIM_N(8) _CASE(8); #endif +#if USED_TIMERS & TIM_N(9) + _CASE(9); +#endif +#if USED_TIMERS & TIM_N(10) + _CASE(10); +#endif +#if USED_TIMERS & TIM_N(11) + _CASE(11); +#endif +#if USED_TIMERS & TIM_N(12) + _CASE(12); +#endif +#if USED_TIMERS & TIM_N(13) + _CASE(13); +#endif +#if USED_TIMERS & TIM_N(14) + _CASE(14); +#endif #if USED_TIMERS & TIM_N(15) _CASE(15); #endif @@ -121,9 +148,36 @@ TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = { #if USED_TIMERS & TIM_N(4) _DEF(4), #endif +#if USED_TIMERS & TIM_N(5) + _DEF(5), +#endif +#if USED_TIMERS & TIM_N(6) + _DEF(6), +#endif +#if USED_TIMERS & TIM_N(7) + _DEF(7), +#endif #if USED_TIMERS & TIM_N(8) _DEF(8), #endif +#if USED_TIMERS & TIM_N(9) + _DEF(9), +#endif +#if USED_TIMERS & TIM_N(10) + _DEF(10), +#endif +#if USED_TIMERS & TIM_N(11) + _DEF(11), +#endif +#if USED_TIMERS & TIM_N(12) + _DEF(12), +#endif +#if USED_TIMERS & TIM_N(13) + _DEF(13), +#endif +#if USED_TIMERS & TIM_N(14) + _DEF(14), +#endif #if USED_TIMERS & TIM_N(15) _DEF(15), #endif From e0edd563c66dd4932cd29c3aba5470852f2e372c Mon Sep 17 00:00:00 2001 From: flyinglemonfpv Date: Sun, 10 Jul 2016 15:15:37 +0200 Subject: [PATCH 091/108] target.h updated for new UART, I2C and LEDSTRIP IO --- src/main/target/AIR32/target.h | 53 +++++++++------------------------- 1 file changed, 13 insertions(+), 40 deletions(-) diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 754e9324ee..3e60de5031 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -63,45 +63,25 @@ //#define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN GPIO_Pin_3 // PB3 -#define UART2_RX_PIN GPIO_Pin_4 // PB4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 + +#define UART3_TX_PIN PB10 //(AF7) +#define UART3_RX_PIN PB11 //(AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) - -#define I2C2_SCL_GPIO GPIOA -#define I2C2_SCL_GPIO_AF GPIO_AF_4 -#define I2C2_SCL_PIN PA9 -#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 -#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA -#define I2C2_SDA_GPIO GPIOA -#define I2C2_SDA_GPIO_AF GPIO_AF_4 -#define I2C2_SDA_PIN PA10 -#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 -#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 #define USE_SPI #define USE_SPI_DEVICE_2 @@ -126,16 +106,10 @@ #define LED_STRIP #if 1 -#define LED_STRIP_TIMER TIM16 #define USE_LED_STRIP_ON_DMA1_CHANNEL3 -#define WS2811_GPIO GPIOB -#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_GPIO_AF GPIO_AF_1 -#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 -#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_PIN PB8 // TIM16_CH1 #define WS2811_TIMER TIM16 -#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 #define WS2811_DMA_CHANNEL DMA1_Channel3 #define WS2811_IRQ DMA1_Channel3_IRQn #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 @@ -146,7 +120,6 @@ // Alternate LED strip pin // FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1 #define LED_STRIP_TIMER TIM17 - #define USE_LED_STRIP_ON_DMA1_CHANNEL7 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA From e662257a21ecab6bd9421a1d1683a1e757c88241 Mon Sep 17 00:00:00 2001 From: SergDoc Date: Fri, 1 Jul 2016 21:53:09 +0300 Subject: [PATCH 092/108] fix target F4BY a new firmware Conflicts: src/main/target/F4BY/target.c src/main/target/F4BY/target.h --- src/main/target/F4BY/target.c | 39 ++++++++------- src/main/target/F4BY/target.h | 91 ++++++++++++++++++----------------- 2 files changed, 68 insertions(+), 62 deletions(-) diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index 472d1e8017..e023d7e960 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -14,6 +14,7 @@ const uint16_t multiPPM[] = { PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), PWM15 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed PWM7 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed @@ -30,8 +31,8 @@ const uint16_t multiPWM[] = { PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), PWM6 | (MAP_TO_PWM_INPUT << 8), - PWM7 | (MAP_TO_PWM_INPUT << 8), - PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8 PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -83,22 +84,24 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S1_IN - { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S2_IN - { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S3_IN - { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S4_IN - { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S5_IN - { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S6_IN - { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S7_IN - { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM4, 0}, // S8_IN + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S1_OUT - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S2_OUT - { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S3_OUT - { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S4_OUT - { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S5_OUT - { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S6_OUT - { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S7_OUT - { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM1, 0}, // S8_OUT + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT + { TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT + { TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT + { TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT + { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT + { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT + { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT + + { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed }; diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index c27aa4a386..127a33d4bb 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -58,45 +58,53 @@ #define USE_SDCARD -#define SDCARD_SPI_INSTANCE SPI3 +#define SDCARD_SPI_INSTANCE SPI2 #define SDCARD_SPI_CS_PIN PE15 -// SPI3 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 // Divide to under 25MHz for normal operation: -#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz -#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 -#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream3 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF3 #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 #define SDCARD_DMA_CHANNEL DMA_Channel_0 -// Performance logging for SD card operations: -#define USABLE_TIMER_CHANNEL_COUNT 16 +#define USABLE_TIMER_CHANNEL_COUNT 17 #define USE_VCP #define VBUS_SENSING_PIN PA9 -#define USE_USART1 -#define USART1_RX_PIN PB7 -#define USART1_TX_PIN PB6 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART2 -#define USART2_RX_PIN PD6 -#define USART2_TX_PIN PD5 +#define USE_UART2 +#define UART2_RX_PIN PD6 +#define UART2_TX_PIN PD5 -#define USE_USART3 -#define USART3_RX_PIN PD9 -#define USART3_TX_PIN PD8 +#define USE_UART3 +#define UART3_RX_PIN PD9 +#define UART3_TX_PIN PD8 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +//#define USE_UART5 - error in DMA!!! +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6 #define USE_SPI @@ -106,12 +114,18 @@ #define SPI1_MOSI_PIN PA7 #define SPI1_NSS_PIN NONE +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN NONE +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 #define USE_SPI_DEVICE_3 -#define SPI3_NSS_PIN NONE -#define SPI2_SCK_PIN PB3 -#define SPI2_MISO_PIN PB4 -#define SPI2_MOSI_PIN PB5 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + #define USE_I2C @@ -121,31 +135,20 @@ #define I2C2_SDA PB11 #define USE_ADC -//#define BOARD_HAS_VOLTAGE_DIVIDER +#define BOARD_HAS_VOLTAGE_DIVIDER #define VBAT_ADC_PIN PC3 #define CURRENT_METER_ADC_PIN PC2 #define RSSI_ADC_PIN PC1 - -#define SENSORS_SET (SENSOR_ACC) - - -// alternative defaults for F4BY -//#define F4BY - -#define SPEKTRUM_BIND -// USART6, PC7 -#define BIND_PIN PC7 - -#define HARDWARE_BIND_PLUG -// Hardware bind plug at PB2 (Pin 28) -#define BINDPLUG_PIN PB2 +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define BRUSHED_MOTORS -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES (FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) +#define SPEKTRUM_BIND +// UART6, PC7 +#define BIND_PIN PC7 #define USE_SERIAL_4WAY_BLHELI_INTERFACE @@ -155,5 +158,5 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff -#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) +#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9)) From 741dee6d6ddf07a224b3bcd6fef1073612686a5e Mon Sep 17 00:00:00 2001 From: nathan Date: Sun, 10 Jul 2016 20:34:42 -0700 Subject: [PATCH 093/108] preprocessor defines for spi mpu6000 and spi bmp280, check for the button feature, not specific targets --- src/main/drivers/accgyro_spi_mpu6000.c | 5 +++++ src/main/drivers/barometer_spi_bmp280.c | 2 ++ src/main/main.c | 2 +- 3 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index 8c277dea5c..cb565b6430 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -41,6 +41,9 @@ #include "sensor.h" #include "accgyro.h" #include "accgyro_mpu.h" + +#if defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_SPI_MPU6000) + #include "accgyro_spi_mpu6000.h" static void mpu6000AccAndGyroInit(void); @@ -283,3 +286,5 @@ bool mpu6000SpiGyroDetect(gyro_t *gyro) return true; } + +#endif diff --git a/src/main/drivers/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c index d7a7491959..23b1cbf87e 100644 --- a/src/main/drivers/barometer_spi_bmp280.c +++ b/src/main/drivers/barometer_spi_bmp280.c @@ -28,6 +28,7 @@ #include "barometer.h" #include "barometer_bmp280.h" +#ifdef USE_BARO_SPI_BMP280 #define DISABLE_BMP280 IOHi(bmp280CsPin) #define ENABLE_BMP280 IOLo(bmp280CsPin) @@ -91,3 +92,4 @@ void bmp280_spi_get_up(void) bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4)); bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4)); } +#endif diff --git a/src/main/main.c b/src/main/main.c index a411117617..8cf45ac7bb 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -193,7 +193,7 @@ void init(void) EXTIInit(); #endif -#if defined(SPRACINGF3MINI) || defined(OMNIBUS) +#if defined(BUTTONS) gpio_config_t buttonAGpioConfig = { BUTTON_A_PIN, Mode_IPU, From 8cb9db535653b8723670255db468db5401322f5e Mon Sep 17 00:00:00 2001 From: johnlemon Date: Mon, 11 Jul 2016 11:16:29 +0200 Subject: [PATCH 094/108] Update target.c --- src/main/target/AIR32/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/AIR32/target.c b/src/main/target/AIR32/target.c index 47789fd4f8..9603f1688c 100644 --- a/src/main/target/AIR32/target.c +++ b/src/main/target/AIR32/target.c @@ -1,8 +1,8 @@ -#include #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { From ec105beb9c89627971531e45eaa2f7dbc26ffb4f Mon Sep 17 00:00:00 2001 From: johnlemon Date: Mon, 11 Jul 2016 12:12:02 +0200 Subject: [PATCH 095/108] target.c compile warnings --- src/main/target/AIR32/target.c | 35 ++++++++++++++++++++++++---------- 1 file changed, 25 insertions(+), 10 deletions(-) diff --git a/src/main/target/AIR32/target.c b/src/main/target/AIR32/target.c index 9603f1688c..378627daaf 100644 --- a/src/main/target/AIR32/target.c +++ b/src/main/target/AIR32/target.c @@ -1,3 +1,19 @@ +/* + * 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 . + */ #include @@ -42,14 +58,13 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; - From e79a0ffa1a6ab294c2500ccc0ed579754fe872ba Mon Sep 17 00:00:00 2001 From: Anders Hoglund Date: Mon, 11 Jul 2016 12:24:47 +0200 Subject: [PATCH 096/108] include of nvic.h missing in transponder.c, complie failed. --- src/main/drivers/transponder_ir.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/transponder_ir.c b/src/main/drivers/transponder_ir.c index 8e95ac33bf..2faf37731d 100644 --- a/src/main/drivers/transponder_ir.c +++ b/src/main/drivers/transponder_ir.c @@ -24,6 +24,7 @@ #include "build_config.h" #include "drivers/dma.h" +#include "drivers/nvic.h" #include "drivers/transponder_ir.h" /* From 3d8ee5093404c25f96eb6757cb5feb05e7133e49 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 11 Jul 2016 18:45:35 +0100 Subject: [PATCH 097/108] Removed unnecesary #includes from drivers --- src/main/drivers/accgyro_lsm303dlhc.c | 1 - src/main/drivers/accgyro_mpu6500.c | 1 - src/main/drivers/accgyro_spi_mpu6000.c | 1 - src/main/drivers/accgyro_spi_mpu6500.c | 1 - src/main/drivers/accgyro_spi_mpu9250.c | 1 - src/main/drivers/barometer_spi_bmp280.c | 3 --- src/main/drivers/bus_i2c_stm32f10x.c | 2 -- src/main/drivers/bus_i2c_stm32f30x.c | 3 --- src/main/drivers/bus_spi.c | 2 -- src/main/drivers/compass_hmc5883l.c | 1 - src/main/drivers/display_ug2864hsweg01.c | 1 - src/main/drivers/dma.c | 2 -- src/main/drivers/dma_stm32f4xx.c | 4 +--- src/main/drivers/exti.c | 2 +- src/main/drivers/flash_m25p16.c | 1 - src/main/drivers/gpio_stm32f30x.c | 2 -- src/main/drivers/gyro_sync.c | 1 - src/main/drivers/max7456.c | 4 +--- src/main/drivers/pwm_mapping.c | 1 - src/main/drivers/pwm_rx.c | 3 +-- src/main/drivers/sdcard.c | 5 ++--- src/main/drivers/serial_softserial.c | 1 - src/main/drivers/serial_uart.c | 1 - src/main/drivers/serial_uart_stm32f10x.c | 1 - src/main/drivers/serial_uart_stm32f30x.c | 1 - src/main/drivers/serial_uart_stm32f4xx.c | 1 - src/main/drivers/serial_usb_vcp.c | 2 -- src/main/drivers/sound_beeper.c | 3 --- src/main/drivers/system.c | 4 ---- src/main/drivers/system_stm32f10x.c | 3 +-- src/main/drivers/system_stm32f30x.c | 3 +-- src/main/drivers/system_stm32f4xx.c | 12 ++---------- src/main/drivers/transponder_ir.c | 3 --- src/main/drivers/usb_detection.c | 1 - src/main/drivers/usb_io.c | 8 ++++---- src/main/drivers/vtx_rtc6705.c | 1 - src/main/drivers/vtx_soft_spi_rtc6705.c | 1 - 37 files changed, 14 insertions(+), 74 deletions(-) diff --git a/src/main/drivers/accgyro_lsm303dlhc.c b/src/main/drivers/accgyro_lsm303dlhc.c index 4caed30911..c3ea4968e7 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.c +++ b/src/main/drivers/accgyro_lsm303dlhc.c @@ -19,7 +19,6 @@ #include #include "platform.h" -#include "build_config.h" #include "debug.h" #include "common/maths.h" diff --git a/src/main/drivers/accgyro_mpu6500.c b/src/main/drivers/accgyro_mpu6500.c index 0cc23cfa9b..ed872230ea 100644 --- a/src/main/drivers/accgyro_mpu6500.c +++ b/src/main/drivers/accgyro_mpu6500.c @@ -20,7 +20,6 @@ #include #include "platform.h" -#include "build_config.h" #include "common/axis.h" #include "common/maths.h" diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index 8c277dea5c..aa2d7696e7 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -24,7 +24,6 @@ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 32ae6a1ce8..afc69fbf16 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 219bd51a21..b5beca2946 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -25,7 +25,6 @@ #include #include -#include #include "platform.h" #include "light_led.h" diff --git a/src/main/drivers/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c index d7a7491959..a32d6d1176 100644 --- a/src/main/drivers/barometer_spi_bmp280.c +++ b/src/main/drivers/barometer_spi_bmp280.c @@ -17,12 +17,9 @@ #include #include -#include #include -#include "build_config.h" - #include "bus_spi.h" #include "barometer.h" diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 281db6bf2d..74a9f36559 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -21,8 +21,6 @@ #include -#include "build_config.h" - #include "io.h" #include "system.h" diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 58d0caff31..d645a70504 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -17,12 +17,9 @@ #include #include -#include #include -#include "build_config.h" - #include "gpio.h" #include "system.h" #include "drivers/io_impl.h" diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 2eefe6edc6..005f7936b6 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -20,8 +20,6 @@ #include -#include "build_config.h" - #include "bus_spi.h" #include "io.h" #include "io_impl.h" diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index c8c398fc3d..68c404d804 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -17,7 +17,6 @@ #include #include -#include #include diff --git a/src/main/drivers/display_ug2864hsweg01.c b/src/main/drivers/display_ug2864hsweg01.c index d16798e042..84ad2b4c2b 100644 --- a/src/main/drivers/display_ug2864hsweg01.c +++ b/src/main/drivers/display_ug2864hsweg01.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index 4b6cace0e5..0ad411312e 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -21,8 +21,6 @@ #include -#include "build_config.h" - #include "drivers/nvic.h" #include "drivers/dma.h" diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index bf2d2ec582..ce960ab4c2 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -16,13 +16,11 @@ */ #include -#include #include +#include #include -#include "build_config.h" - #include "drivers/nvic.h" #include "drivers/dma.h" diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index e876f7a6be..cd97ba9b74 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -1,6 +1,6 @@ -#include #include #include +#include #include "platform.h" diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index c788dd8fe1..806c777dab 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -15,7 +15,6 @@ * along with Cleanflight. If not, see . */ -#include #include #include diff --git a/src/main/drivers/gpio_stm32f30x.c b/src/main/drivers/gpio_stm32f30x.c index 279f1acee3..ee54ab8a90 100644 --- a/src/main/drivers/gpio_stm32f30x.c +++ b/src/main/drivers/gpio_stm32f30x.c @@ -20,8 +20,6 @@ #include "platform.h" -#include "build_config.h" - #include "gpio.h" #define MODE_OFFSET 0 diff --git a/src/main/drivers/gyro_sync.c b/src/main/drivers/gyro_sync.c index 61305e1819..cd95e186e1 100644 --- a/src/main/drivers/gyro_sync.c +++ b/src/main/drivers/gyro_sync.c @@ -9,7 +9,6 @@ #include #include "platform.h" -#include "build_config.h" #include "drivers/sensor.h" #include "drivers/accgyro.h" diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 793f6f77eb..b9f521273c 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -15,17 +15,15 @@ * along with Cleanflight. If not, see . */ -#include #include -#include #include -#include "common/printf.h" #include "platform.h" #include "version.h" #ifdef USE_MAX7456 +#include "common/printf.h" #include "drivers/bus_spi.h" #include "drivers/light_led.h" #include "drivers/system.h" diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 80d2b01d92..13f01eac42 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -18,7 +18,6 @@ #include #include #include -#include #include "platform.h" diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index a0f65f4e3a..cde900c52b 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -18,9 +18,8 @@ #include #include -#include - #include + #include "build_config.h" #include "debug.h" diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index 722715fc16..3813fed74b 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -15,12 +15,13 @@ * along with Cleanflight. If not, see . */ -#include #include #include #include "platform.h" +#ifdef USE_SDCARD + #include "nvic.h" #include "io.h" @@ -30,8 +31,6 @@ #include "sdcard.h" #include "sdcard_standard.h" -#ifdef USE_SDCARD - #ifdef AFATFS_USE_INTROSPECTIVE_LOGGING #define SDCARD_PROFILING #endif diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index e44ff10a33..51cdeb2936 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 3bee96b89e..ced8d97fff 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -22,7 +22,6 @@ */ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 330b3f837a..4774ab33e6 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -24,7 +24,6 @@ #include #include -#include #include diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index ee65d54d2d..09b6663e86 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -25,7 +25,6 @@ #include #include -#include #include diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 91577628b0..97f087a510 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -17,7 +17,6 @@ #include #include -#include #include "platform.h" diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 5f1b223918..f225dd62bb 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -16,9 +16,7 @@ */ #include -#include #include -#include #include "platform.h" diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index 0c60ca4eb4..44d968db0b 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -17,12 +17,9 @@ #include #include -#include #include "platform.h" -#include "common/utils.h" - #include "system.h" #include "io.h" diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 9efa3e4440..962b637349 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -15,15 +15,11 @@ * along with Cleanflight. If not, see . */ -#include #include #include -#include #include "platform.h" -#include "build_config.h" - #include "gpio.h" #include "light_led.h" #include "sound_beeper.h" diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index c273c6f3dc..f5eab63fac 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -15,10 +15,9 @@ * along with Cleanflight. If not, see . */ -#include #include #include -#include +#include #include "platform.h" diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index d762e2c333..e0aaad1bb0 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -15,10 +15,9 @@ * along with Cleanflight. If not, see . */ -#include #include #include -#include +#include #include "platform.h" diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index e7587aa9b3..8101974377 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -15,26 +15,18 @@ * along with Cleanflight. If not, see . */ -#include #include #include -#include +#include #include "platform.h" +#include "accgyro_mpu.h" #include "gpio.h" #include "nvic.h" #include "system.h" - #include "exti.h" -#include "debug.h" -#include "sensor.h" -#include "accgyro.h" -#include "accgyro_mpu.h" -#include "accgyro_spi_mpu6000.h" -#include "accgyro_mpu6500.h" -#include "accgyro_spi_mpu9250.h" #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) diff --git a/src/main/drivers/transponder_ir.c b/src/main/drivers/transponder_ir.c index 2faf37731d..792e26beff 100644 --- a/src/main/drivers/transponder_ir.c +++ b/src/main/drivers/transponder_ir.c @@ -17,12 +17,9 @@ #include #include -#include #include -#include "build_config.h" - #include "drivers/dma.h" #include "drivers/nvic.h" #include "drivers/transponder_ir.h" diff --git a/src/main/drivers/usb_detection.c b/src/main/drivers/usb_detection.c index 13cc8bb1cb..9279d7dff4 100644 --- a/src/main/drivers/usb_detection.c +++ b/src/main/drivers/usb_detection.c @@ -15,7 +15,6 @@ * along with Cleanflight. If not, see . */ -#include #include #include diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index 14a01bcd65..d8a7206109 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -15,19 +15,19 @@ * along with Cleanflight. If not, see . */ -#include "sdcard.h" - -#include #include #include #include "platform.h" +#ifdef USB_IO + #include "io.h" #include "system.h" #include "usb_io.h" +#include "sdcard.h" + -#ifdef USB_IO #ifdef USB_DETECT_PIN static IO_t usbDetectPin = IO_NONE; diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index 35e78fe0dc..ee540da60e 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -22,7 +22,6 @@ * as this header is maintained with the file at all times. */ -#include #include #include diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c index 6572540c66..4ceba50df9 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.c +++ b/src/main/drivers/vtx_soft_spi_rtc6705.c @@ -15,7 +15,6 @@ * along with Cleanflight. If not, see . */ -#include #include #include From c076bc3e2d47b8299aa21ba1b84f066f7f30b31c Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 11 Jul 2016 20:11:09 +0100 Subject: [PATCH 098/108] Minor build optimisations --- src/main/io/display.c | 8 +++----- src/main/io/gps.c | 5 +++-- src/main/io/rc_curves.c | 1 - src/main/io/serial.c | 5 +---- src/main/sensors/acceleration.c | 12 +++++------- src/main/sensors/barometer.c | 1 - src/main/sensors/battery.c | 4 +--- src/main/sensors/compass.c | 1 - 8 files changed, 13 insertions(+), 24 deletions(-) diff --git a/src/main/io/display.c b/src/main/io/display.c index a61b64f276..1e5eee9746 100644 --- a/src/main/io/display.c +++ b/src/main/io/display.c @@ -17,10 +17,12 @@ #include #include -#include #include #include "platform.h" + +#ifdef DISPLAY + #include "version.h" #include "debug.h" @@ -38,16 +40,12 @@ #include "common/axis.h" #include "common/typeconversion.h" -#ifdef DISPLAY - #include "sensors/battery.h" #include "sensors/sensors.h" #include "sensors/compass.h" #include "sensors/acceleration.h" #include "sensors/gyro.h" -#include "rx/rx.h" - #include "io/rc_controls.h" #include "flight/pid.h" diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 3006d09114..cf8e141aec 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -23,6 +23,9 @@ #include #include "platform.h" + +#ifdef GPS + #include "build_config.h" #include "debug.h" @@ -50,8 +53,6 @@ #include "config/runtime_config.h" -#ifdef GPS - #define LOG_ERROR '?' #define LOG_IGNORED '!' #define LOG_SKIPPED '>' diff --git a/src/main/io/rc_curves.c b/src/main/io/rc_curves.c index ee2fe326f0..89b46522f2 100644 --- a/src/main/io/rc_curves.c +++ b/src/main/io/rc_curves.c @@ -18,7 +18,6 @@ #include #include -#include "rx/rx.h" #include "io/rc_controls.h" #include "io/escservo.h" diff --git a/src/main/io/serial.c b/src/main/io/serial.c index be6372b479..890e218280 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -17,7 +17,6 @@ #include #include -#include #include #include "platform.h" @@ -36,9 +35,8 @@ #include "drivers/serial_uart.h" #endif -#include "drivers/gpio.h" #include "drivers/light_led.h" - + #if defined(USE_VCP) #include "drivers/serial_usb_vcp.h" #endif @@ -47,7 +45,6 @@ #include "serial_cli.h" #include "serial_msp.h" -#include "config/config.h" #ifdef TELEMETRY #include "telemetry/telemetry.h" diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index da86d37eb4..5de9c3fce9 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -29,11 +29,9 @@ #include "drivers/accgyro.h" #include "drivers/system.h" -#include "sensors/battery.h" #include "sensors/sensors.h" #include "io/beeper.h" #include "sensors/boardalignment.h" -#include "config/runtime_config.h" #include "config/config.h" #include "sensors/acceleration.h" @@ -67,12 +65,12 @@ bool isAccelerationCalibrationComplete(void) return calibratingA == 0; } -bool isOnFinalAccelerationCalibrationCycle(void) +static bool isOnFinalAccelerationCalibrationCycle(void) { return calibratingA == 1; } -bool isOnFirstAccelerationCalibrationCycle(void) +static bool isOnFirstAccelerationCalibrationCycle(void) { return calibratingA == CALIBRATING_ACC_CYCLES; } @@ -83,7 +81,7 @@ void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims) rollAndPitchTrims->values.pitch = 0; } -void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) +static void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) { static int32_t a[3]; @@ -115,7 +113,7 @@ void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) calibratingA--; } -void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) +static void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims) { uint8_t axis; static int32_t b[3]; @@ -168,7 +166,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri } } -void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims) +static void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims) { accSmooth[X] -= accelerationTrims->raw[X]; accSmooth[Y] -= accelerationTrims->raw[Y]; diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 2d7b44e551..9e428ad7ee 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -28,7 +28,6 @@ int32_t BaroAlt = 0; #include "drivers/barometer.h" #include "drivers/system.h" -#include "config/config.h" #include "sensors/barometer.h" diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index c6e3be93ca..59fa7ef9ae 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -32,8 +32,6 @@ #include "sensors/battery.h" -#include "rx/rx.h" - #include "io/rc_controls.h" #include "io/beeper.h" @@ -170,7 +168,7 @@ void batteryInit(batteryConfig_t *initialBatteryConfig) } #define ADCVREF 3300 // in mV -int32_t currentSensorToCentiamps(uint16_t src) +static int32_t currentSensorToCentiamps(uint16_t src) { int32_t millivolts; diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index cca2328c04..6f6735d0fe 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -25,7 +25,6 @@ #include "drivers/sensor.h" #include "drivers/compass.h" #include "drivers/compass_hmc5883l.h" -#include "drivers/gpio.h" #include "drivers/light_led.h" #include "sensors/boardalignment.h" From 9616c397eae69963b6c96e4f2efbb492dfd8fe39 Mon Sep 17 00:00:00 2001 From: kc10kevin Date: Mon, 11 Jul 2016 18:13:57 -0500 Subject: [PATCH 099/108] SDCard Detect/Delay Fix --- src/main/drivers/sdcard.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index 722715fc16..e52b19a7d2 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -44,7 +44,7 @@ // Chosen so that CMD8 will have the same CRC as CMD0: #define SDCARD_IF_COND_CHECK_PATTERN 0xAB -#define SDCARD_TIMEOUT_INIT_MILLIS 2000 +#define SDCARD_TIMEOUT_INIT_MILLIS 200 #define SDCARD_MAX_CONSECUTIVE_FAILURES 8 /* Break up 512-byte SD card sectors into chunks of this size when writing without DMA to reduce the peak overhead From 57372cf234ade3bd61470788c85c665a5680e6a6 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 12 Jul 2016 09:10:37 +0100 Subject: [PATCH 100/108] Replaced #include with forward reference --- src/main/telemetry/telemetry.h | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index 8e692c4028..b4585e5fce 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -21,10 +21,8 @@ * Created on: 6 Apr 2014 * Author: Hydra */ -#include "rx/rx.h" -#ifndef TELEMETRY_COMMON_H_ -#define TELEMETRY_COMMON_H_ +#pragma once typedef enum { FRSKY_FORMAT_DMS = 0, @@ -39,9 +37,9 @@ typedef enum { typedef struct telemetryConfig_s { uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed. uint8_t telemetry_inversion; // also shared with smartport inversion - float gpsNoFixLatitude; - float gpsNoFixLongitude; - frskyGpsCoordFormat_e frsky_coordinate_format; + float gpsNoFixLatitude; + float gpsNoFixLongitude; + frskyGpsCoordFormat_e frsky_coordinate_format; frskyUnit_e frsky_unit; uint8_t frsky_vfas_precision; uint8_t frsky_vfas_cell_voltage; @@ -52,7 +50,8 @@ bool telemetryCheckRxPortShared(serialPortConfig_t *portConfig); extern serialPort_t *telemetrySharedPort; void telemetryCheckState(void); -void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle); +struct rxConfig_s; +void telemetryProcess(struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle); bool telemetryDetermineEnabledState(portSharing_e portSharing); @@ -60,4 +59,3 @@ void telemetryUseConfig(telemetryConfig_t *telemetryConfig); #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM) -#endif /* TELEMETRY_COMMON_H_ */ From 473d78790e03fad836c26fdd61f5636bf0de8158 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 12 Jul 2016 21:19:53 +1000 Subject: [PATCH 101/108] Disable IRQs whilst transferring bytes on VCP (F4) --- src/main/vcpf4/usbd_cdc_vcp.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 5672eeae55..42913891ea 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -223,6 +223,8 @@ static uint32_t rxPackets = 0; static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) { + __disable_irq(); + rxPackets++; for (uint32_t i = 0; i < Len; i++) { @@ -232,6 +234,7 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) rxTotalBytes++; } + __enable_irq(); if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; From 9800b47acda7159e9e865e360a27190bac1436a2 Mon Sep 17 00:00:00 2001 From: TheAngularity Date: Tue, 12 Jul 2016 14:25:06 +0200 Subject: [PATCH 102/108] fixed compile error on transponder_ir.c ... %% transponder_ir.c ./src/main/drivers/transponder_ir.c: In function 'transponderIrInit': ./src/main/drivers/transponder_ir.c:52:5: warning: implicit declaration of function 'memset' [-Wimplicit-function-declaration] memset(&transponderIrDMABuffer, 0, TRANSPONDER_DMA_BUFFER_SIZE); ^ ./src/main/drivers/transponder_ir.c:52:5: warning: incompatible implicit declaration of built-in function 'memset' ./src/main/drivers/transponder_ir.c:52:5: note: include '' or provide a declaration of 'memset' %% blackbox.c ... --- src/main/drivers/transponder_ir.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/transponder_ir.c b/src/main/drivers/transponder_ir.c index 792e26beff..626c60097c 100644 --- a/src/main/drivers/transponder_ir.c +++ b/src/main/drivers/transponder_ir.c @@ -17,6 +17,7 @@ #include #include +#include #include From 1204c772966f02183a5585e7054f29e837db8c43 Mon Sep 17 00:00:00 2001 From: nathan Date: Wed, 13 Jul 2016 00:30:59 -0700 Subject: [PATCH 103/108] omnibus pinout updates, osd dma mapping --- src/main/target/OMNIBUS/target.c | 22 ++++--- src/main/target/OMNIBUS/target.h | 96 ++++++++++++++----------------- src/main/target/OMNIBUS/target.mk | 8 +-- 3 files changed, 55 insertions(+), 71 deletions(-) diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index a41891d696..977d623f85 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -85,20 +85,18 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent - // Used by SPI1, MAX7456 - //{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - //{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9 - { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM5 - PA2 - { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM6 - PA3 - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA0 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM4 - PA3 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7) + + // SDA / SCL + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB7 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8 - PB6 // LED Strip Pad { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index bab30522f7..7f59fed66f 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -30,39 +30,38 @@ #define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect -#define USE_EXTI -#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - -#define USE_MAG_DATA_READY_SIGNAL -#define ENSURE_MAG_DATA_READY_IS_HIGH +#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) +#define MPU_INT_EXTI PC13 +#define USE_EXTI +#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 #define GYRO -//#define USE_FAKE_GYRO -#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW90_DEG #define ACC -//#define USE_FAKE_ACC -#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define GYRO_MPU6500_ALIGN CW90_DEG -#define ACC_MPU6500_ALIGN CW180_DEG -#define GYRO_MPU6500_ALIGN CW180_DEG +#define BMP280_SPI_INSTANCE SPI1 +#define BMP280_CS_PIN PA13 #define BARO #define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 -#define MAG -#define USE_MPU9250_MAG // Enables bypass configuration -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 // External +//#define MAG +//#define USE_MAG_AK8975 +//#define USE_MAG_HMC5883 // External +// +//#define MAG_AK8975_ALIGN CW90_DEG_FLIP -#define MAG_AK8975_ALIGN CW90_DEG_FLIP - -#define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +//#define SONAR +//#define SONAR_ECHO_PIN PB1 +//#define SONAR_TRIGGER_PIN PB0 #define USB_IO #define USB_CABLE_DETECTION @@ -73,8 +72,7 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 4 #define UART1_TX_PIN PA9 // PA9 #define UART1_RX_PIN PA10 // PA10 @@ -85,13 +83,8 @@ #define UART3_TX_PIN PB10 // PB10 (AF7) #define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM2 -#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3 -#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4 - -#define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA - +//#define USE_I2C +//#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 @@ -108,14 +101,13 @@ // include the max7456 driver #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI1 -#define MAX7456_SPI_CS_PIN SPI1_NSS_PIN -#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3 -//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2 // <- Conflicts with WS2811 DMA -#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER +#define MAX7456_SPI_CS_PIN PB1 +//#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3 +//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2 +//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 @@ -144,21 +136,23 @@ // #define AFATFS_USE_INTROSPECTIVE_LOGGING #define USE_ADC -#define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +//#define BOARD_HAS_VOLTAGE_DIVIDER +#define VBAT_ADC_PIN PA0 +#define CURRENT_METER_ADC_PIN PA1 +#define ADC_INSTANCE ADC1 + +//#define RSSI_ADC_PIN PB1 +//#define ADC_INSTANCE ADC3 -#define LED_STRIP - -#define WS2811_PIN PA8 -#define WS2811_TIMER TIM1 -#define WS2811_DMA_CHANNEL DMA1_Channel2 -#define WS2811_IRQ DMA1_Channel2_IRQn -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER +//#define LED_STRIP +// +//#define WS2811_PIN PA8 +//#define WS2811_TIMER TIM1 +//#define WS2811_DMA_CHANNEL DMA1_Channel2 +//#define WS2811_IRQ DMA1_Channel2_IRQn +//#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +//#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER //#define TRANSPONDER @@ -178,7 +172,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES FEATURE_BLACKBOX +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define BUTTONS #define BUTTON_A_PORT GPIOB @@ -201,7 +195,3 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) - -#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) -#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15) -#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) diff --git a/src/main/target/OMNIBUS/target.mk b/src/main/target/OMNIBUS/target.mk index 1cb198e263..26a246adcd 100644 --- a/src/main/target/OMNIBUS/target.mk +++ b/src/main/target/OMNIBUS/target.mk @@ -3,15 +3,11 @@ FEATURES = VCP SDCARD TARGET_SRC = \ drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6000.c \ drivers/barometer_bmp280.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/flash_m25p16.c \ + drivers/barometer_spi_bmp280.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ drivers/serial_usb_vcp.c \ - drivers/sonar_hcsr04.c \ drivers/max7456.c \ io/osd.c From 7c72816d7bc77064029328b5d0129843479b4bfd Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 13 Jul 2016 19:20:01 +1000 Subject: [PATCH 104/108] Removed tabs --- src/main/vcpf4/usbd_cdc_vcp.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 42913891ea..61e26a1131 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -223,7 +223,7 @@ static uint32_t rxPackets = 0; static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) { - __disable_irq(); + __disable_irq(); rxPackets++; @@ -234,7 +234,7 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) rxTotalBytes++; } - __enable_irq(); + __enable_irq(); if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; From 0e3afca946e947f5009b1aaee9cafc3f684f6fe1 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 13 Jul 2016 19:25:19 +1000 Subject: [PATCH 105/108] fix for OneShot42 issue. --- src/main/drivers/pwm_output.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index fd8446584d..cc5a6073c2 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -118,6 +118,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 p->period = period; p->tim = timerHardware->tim; + *p->ccr = 0; return p; } From e4f9118e82d9e288195c68c9c5e2f5ab2bcae4eb Mon Sep 17 00:00:00 2001 From: borisbstyle Date: Wed, 13 Jul 2016 14:07:32 +0200 Subject: [PATCH 106/108] ident --- src/main/drivers/pwm_output.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index cc5a6073c2..056ee17faa 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -118,7 +118,8 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 p->period = period; p->tim = timerHardware->tim; - *p->ccr = 0; + *p->ccr = 0; + return p; } From 52def80b4fd51581cfbd12e55e584a08111a0f0e Mon Sep 17 00:00:00 2001 From: nathan Date: Wed, 13 Jul 2016 21:40:03 -0700 Subject: [PATCH 107/108] mpu6000 acc not 6500 gyro --- src/main/target/OMNIBUS/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 7f59fed66f..6821d67cbe 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -44,7 +44,7 @@ #define ACC #define USE_ACC_SPI_MPU6000 -#define GYRO_MPU6500_ALIGN CW90_DEG +#define ACC_MPU6000_ALIGN CW90_DEG #define BMP280_SPI_INSTANCE SPI1 #define BMP280_CS_PIN PA13 From 26ee39666e6440dcc71a26f47d8df224a5b69028 Mon Sep 17 00:00:00 2001 From: nathan Date: Wed, 13 Jul 2016 21:40:17 -0700 Subject: [PATCH 108/108] re-enable transponder and ws2811 --- src/main/target/OMNIBUS/target.h | 42 +++++++++++++++---------------- src/main/target/OMNIBUS/target.mk | 3 +++ 2 files changed, 23 insertions(+), 22 deletions(-) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 6821d67cbe..b9119c5fd3 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -145,30 +145,28 @@ //#define ADC_INSTANCE ADC3 -//#define LED_STRIP -// -//#define WS2811_PIN PA8 -//#define WS2811_TIMER TIM1 -//#define WS2811_DMA_CHANNEL DMA1_Channel2 -//#define WS2811_IRQ DMA1_Channel2_IRQn -//#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 -//#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER +#define LED_STRIP +#define WS2811_PIN PA8 +#define WS2811_TIMER TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER +#define TRANSPONDER +#define TRANSPONDER_GPIO GPIOA +#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define TRANSPONDER_GPIO_AF GPIO_AF_6 +#define TRANSPONDER_PIN GPIO_Pin_8 +#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 +#define TRANSPONDER_TIMER TIM1 +#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 +#define TRANSPONDER_IRQ DMA1_Channel2_IRQn +#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 +#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER -//#define TRANSPONDER -//#define TRANSPONDER_GPIO GPIOA -//#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -//#define TRANSPONDER_GPIO_AF GPIO_AF_6 -//#define TRANSPONDER_PIN GPIO_Pin_8 -//#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 -//#define TRANSPONDER_TIMER TIM1 -//#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 -//#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 -//#define TRANSPONDER_IRQ DMA1_Channel2_IRQn -//#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 -//#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER - -//#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT +#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_PPM diff --git a/src/main/target/OMNIBUS/target.mk b/src/main/target/OMNIBUS/target.mk index 26a246adcd..82cde62266 100644 --- a/src/main/target/OMNIBUS/target.mk +++ b/src/main/target/OMNIBUS/target.mk @@ -9,5 +9,8 @@ TARGET_SRC = \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_usb_vcp.c \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/transponder_ir.c \ drivers/max7456.c \ io/osd.c