From cf6c045b42100f9e8f2171bcc8f34c85e6f2acf8 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Sat, 16 Jul 2016 08:41:37 +0100 Subject: [PATCH] Tidied whitespace in target.h files --- src/main/target/CHEBUZZF3/target.h | 37 ++++++------- src/main/target/F4BY/target.h | 14 ++--- src/main/target/OLIMEXINO/target.h | 21 ++++---- src/main/target/OMNIBUS/target.h | 66 +++++++++++------------ src/main/target/PIKOBLX/target.h | 2 +- src/main/target/PORT103R/target.h | 56 ++++++++++---------- src/main/target/SINGULARITY/target.h | 44 ++++++++-------- src/main/target/SIRINFPV/target.h | 73 +++++++++++++------------- src/main/target/SPRACINGF3EVO/target.h | 2 +- src/main/target/X_RACERSPI/target.h | 63 +++++++++++----------- src/main/target/ZCOREF3/target.h | 48 ++++++++--------- 11 files changed, 208 insertions(+), 218 deletions(-) diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index a1d9453e2f..84f7071c86 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -24,12 +24,12 @@ #define STM32F3DISCOVERY #endif -#define LED0 PE8 // Blue LEDs - PE8/PE12 +#define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_INVERTED -#define LED1 PE10 // Orange LEDs - PE10/PE14 +#define LED1 PE10 // Orange LEDs - PE10/PE14 #define LED1_INVERTED -#define BEEPER PE9 // Red LEDs - PE9/PE13 +#define BEEPER PE9 // Red LEDs - PE9/PE13 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 18 @@ -81,16 +81,14 @@ #define ACC #define USE_ACC_MPU6050 #define USE_ACC_LSM303DLHC - -#define ACC_MPU6050_ALIGN CW0_DEG +#define ACC_MPU6050_ALIGN CW0_DEG #define BARO #define USE_BARO_MS5611 #define MAG #define USE_MAG_AK8975 - -#define MAG_AK8975_ALIGN CW90_DEG_FLIP +#define MAG_AK8975_ALIGN CW90_DEG_FLIP #define USE_VCP #define USE_UART1 @@ -101,20 +99,19 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 // IO - assuming 303 in 64pin package, TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#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)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#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)) - -#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)) +#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/F4BY/target.h b/src/main/target/F4BY/target.h index d78895ec84..8b4b846c40 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -132,15 +132,15 @@ #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 USE_ADC +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PC1 -#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125) -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS +#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 diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index d795a22415..bb270cb4fc 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -23,12 +23,12 @@ //#define OLIMEXINO_UNCUT_LED2_E_JUMPER #ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER -#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green +#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green #endif #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/UART2_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 @@ -59,14 +59,14 @@ #define USE_MAG_HMC5883 #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_UART1 #define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 @@ -86,10 +86,9 @@ // IO - assuming all IOs on smt32f103rb LQFP64 package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index b9119c5fd3..87c5c286a9 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -21,9 +21,9 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. @@ -35,19 +35,19 @@ #define MPU_INT_EXTI PC13 #define USE_EXTI -#define MPU6000_SPI_INSTANCE SPI1 -#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW90_DEG +#define ACC_MPU6000_ALIGN CW90_DEG -#define BMP280_SPI_INSTANCE SPI1 -#define BMP280_CS_PIN PA13 +#define BMP280_SPI_INSTANCE SPI1 +#define BMP280_CS_PIN PA13 #define BARO #define USE_BARO_BMP280 @@ -60,13 +60,12 @@ //#define MAG_AK8975_ALIGN CW90_DEG_FLIP //#define SONAR -//#define SONAR_ECHO_PIN PB1 -//#define SONAR_TRIGGER_PIN PB0 +//#define SONAR_ECHO_PIN PB1 +//#define SONAR_TRIGGER_PIN PB0 #define USB_IO #define USB_CABLE_DETECTION - -#define USB_DETECT_PIN PB5 +#define USB_DETECT_PIN PB5 #define USE_VCP #define USE_UART1 @@ -74,14 +73,14 @@ #define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 @@ -100,8 +99,8 @@ #define OSD // include the max7456 driver #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI1 -#define MAX7456_SPI_CS_PIN PB1 +#define MAX7456_SPI_INSTANCE SPI1 +#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 @@ -169,27 +168,28 @@ #define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125) + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define BUTTONS -#define BUTTON_A_PORT GPIOB -#define BUTTON_A_PIN Pin_1 -#define BUTTON_B_PORT GPIOB -#define BUTTON_B_PIN Pin_0 +#define BUTTON_A_PORT GPIOB +#define BUTTON_A_PIN Pin_1 +#define BUTTON_B_PORT GPIOB +#define BUTTON_B_PIN Pin_0 #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define HARDWARE_BIND_PLUG -#define BINDPLUG_PIN PB0 +#define BINDPLUG_PIN PB0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#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(4)) +#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(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index bb6e33717b..111f6fc476 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -134,7 +134,7 @@ #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 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/PORT103R/target.h b/src/main/target/PORT103R/target.h index 22e5a396da..66e83fa3d5 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -19,36 +19,36 @@ #define TARGET_BOARD_IDENTIFIER "103R" -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) -#define LED2 PD2 // PD2 (LED) - Labelled LED4 +#define LED0 PB3 +#define LED1 PB4 +#define LED2 PD2 // PD2 (LED) - Labelled LED4 -#define BEEPER PA12 // PA12 (Beeper) +#define BEEPER PA12 // PA12 (Beeper) -#define BARO_XCLR_GPIO GPIOC -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_GPIO GPIOC -#define BARO_EOC_PIN PC14 -#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC +#define BARO_XCLR_GPIO GPIOC +#define BARO_XCLR_PIN PC13 +#define BARO_EOC_GPIO GPIOC +#define BARO_EOC_PIN PC14 +#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_USART USART2 #define USE_SPI #define USE_SPI_DEVICE_2 -#define PORT103R_SPI_INSTANCE SPI2 -#define PORT103R_SPI_CS_PIN PB12 +#define PORT103R_SPI_INSTANCE SPI2 +#define PORT103R_SPI_CS_PIN PB12 // We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_PIN PORT103R_SPI_CS_PIN -#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define M25P16_CS_PIN PORT103R_SPI_CS_PIN +#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN -#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN +#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN -#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN +#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE #define GYRO #define USE_FAKE_GYRO @@ -93,17 +93,17 @@ #define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define SOFTSERIAL_1_TIMER TIM3 +#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 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_2) +#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) @@ -118,12 +118,10 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f103RCT6 in 64pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) - +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) - diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 06e9f3cfee..09a5678174 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -21,23 +21,23 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define USABLE_TIMER_CHANNEL_COUNT 10 #define USE_EXTI -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP +#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW0_DEG_FLIP +#define ACC_MPU6050_ALIGN CW0_DEG_FLIP #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -49,22 +49,22 @@ #define USE_SOFTSERIAL1 // Telemetry #define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 //Not connected -#define UART2_RX_PIN PA15 +#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 PB10 +#define UART3_RX_PIN PB11 -#define SOFTSERIAL_1_TIMER TIM15 +#define SOFTSERIAL_1_TIMER TIM15 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected #define SOFTSERIAL_1_TIMER_TX_HARDWARE 8 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 // PA4, 5, 6, 7 @@ -81,9 +81,9 @@ #define USE_ADC -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PB2 -#define VBAT_SCALE_DEFAULT 77 +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PB2 +#define VBAT_SCALE_DEFAULT 77 #define LED_STRIP @@ -103,17 +103,17 @@ #define SPEKTRUM_BIND // USART2, PA15 -#define BIND_PIN PA15 +#define BIND_PIN PA15 #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_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 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(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 42f2378c66..0b2ca5f969 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -19,14 +19,14 @@ #define TARGET_BOARD_IDENTIFIER "SIRF" -#define LED0 PB2 -#define BEEPER PA1 +#define LED0 PB2 +#define BEEPER PA1 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT #define USE_EXTI #define USE_MPU_DATA_READY_SIGNAL -#define MPU_INT_EXTI PA8 +#define MPU_INT_EXTI PA8 #define ENSURE_MPU_DATA_READY_IS_LOW #define GYRO @@ -40,18 +40,18 @@ #define USE_ACC_SPI_MPU6500 // MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG -#define GYRO_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 // MPU6500 -#define ACC_MPU6500_ALIGN CW90_DEG -#define GYRO_MPU6500_ALIGN CW90_DEG +#define ACC_MPU6500_ALIGN CW90_DEG +#define GYRO_MPU6500_ALIGN CW90_DEG -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 #define USB_IO @@ -59,16 +59,16 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA2 // PA14 / SWCLK -#define UART2_RX_PIN PA3 // PA15 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #undef USE_I2C @@ -93,17 +93,17 @@ #define SPI3_MOSI_PIN PB5 #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI3 -#define MAX7456_SPI_CS_PIN PA15 +#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_IRQ_HANDLER_ID DMA2_CH1_HANDLER #define USE_RTC6705 -#define RTC6705_SPIDATA_PIN PC15 -#define RTC6705_SPILE_PIN PC14 -#define RTC6705_SPICLK_PIN PC13 +#define RTC6705_SPIDATA_PIN PC15 +#define RTC6705_SPILE_PIN PC14 +#define RTC6705_SPICLK_PIN PC13 #define USE_SDCARD #define USE_SDCARD_SPI2 @@ -124,32 +124,33 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PA0 +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PA0 //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + #define OSD #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define USE_SERVOS -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) #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 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 USABLE_TIMER_CHANNEL_COUNT 6 -#define USED_TIMERS (TIM_N(3) | TIM_N(4)) -#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) -#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB) +#define USED_TIMERS (TIM_N(3) | TIM_N(4)) +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB) diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 704845c1ee..9494f612c5 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -163,5 +163,5 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 4a38e233fb..024a3a6c28 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -22,33 +22,31 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PC14 -#define BEEPER PC15 +#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 MPU6000_CS_PIN PA15 +#define MPU6000_SPI_INSTANCE SPI1 #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#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 MPU_INT_EXTI PC13 #define USE_EXTI @@ -60,27 +58,27 @@ #define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA2 // PA14 / SWCLK -#define UART2_RX_PIN PA3 // PA15 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM3 +#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 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 I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 @@ -100,12 +98,12 @@ #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 USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP @@ -119,21 +117,20 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES FEATURE_BLACKBOX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#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) ) +#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/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index aaa3635da6..c65abb7d92 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -21,32 +21,30 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define LED0 PB8 +#define LED0 PB8 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 #define USE_EXTI -#define MPU_INT_EXTI PC13 +#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 GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW180_DEG #define ACC #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 BARO #define USE_BARO_BMP280 @@ -54,17 +52,17 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 3 +#define SERIAL_PORT_COUNT 3 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) @@ -84,25 +82,25 @@ #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 USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) #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 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 USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )