From 85f7b10e243961cce539197337069522173e8afe Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 17 Jan 2016 02:45:52 +0100 Subject: [PATCH] Fix some F3 target compilation issues. Remove LED_STRIP support from AlienWiiF3 target. It was using sparky source but Sparky has led strip signal on a PWM motor output due to hardware mappings and that doesn't make sense for the AlienWiiF3 target which is has brushed motor circuitry. --- Makefile | 60 +++++++++- src/main/target/CHEBUZZF3/target.h | 127 ---------------------- src/main/target/STM32F3DISCOVERY/target.h | 109 ------------------- 3 files changed, 54 insertions(+), 242 deletions(-) delete mode 100644 src/main/target/CHEBUZZF3/target.h delete mode 100644 src/main/target/STM32F3DISCOVERY/target.h diff --git a/Makefile b/Makefile index d6e079fa7..1a4ec4ca5 100644 --- a/Makefile +++ b/Makefile @@ -527,8 +527,6 @@ STM32F30x_COMMON_SRC = \ drivers/bus_spi.c \ drivers/gpio_stm32f30x.c \ drivers/light_led_stm32f30x.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ drivers/pwm_mapping.c \ drivers/pwm_output.c \ drivers/pwm_rx.c \ @@ -547,6 +545,8 @@ NAZE32PRO_SRC = \ STM32F3DISCOVERY_COMMON_SRC = \ $(STM32F30x_COMMON_SRC) \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ drivers/accgyro_l3gd20.c \ drivers/accgyro_l3gd20.c \ drivers/accgyro_lsm303dlhc.c \ @@ -585,6 +585,9 @@ COLIBRI_RACE_SRC = \ drivers/barometer_ms5611.c \ drivers/compass_ak8975.c \ drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_usb_vcp.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ @@ -613,25 +616,36 @@ SPARKY_SRC = \ drivers/barometer_ms5611.c \ drivers/barometer_bmp280.c \ drivers/compass_ak8975.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ drivers/serial_usb_vcp.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ $(VCP_SRC) ALIENFLIGHTF3_SRC = \ - $(SPARKY_SRC) \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu.c \ drivers/accgyro_mpu6500.c \ drivers/accgyro_spi_mpu6500.c \ drivers/compass_ak8963.c \ - hardware_revision.c + hardware_revision.c \ + drivers/serial_usb_vcp.c \ + drivers/sonar_hcsr04.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) RMDO_SRC = \ $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ drivers/barometer_bmp280.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 \ io/flashfs.c \ @@ -649,6 +663,8 @@ SPRACINGF3_SRC = \ 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 \ io/flashfs.c \ @@ -663,7 +679,10 @@ IRCFUSIONF3_SRC = \ drivers/compass_ak8975.c \ drivers/barometer_bmp085.c \ drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.h \ + drivers/display_ug2864hsweg01.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ drivers/flash_m25p16.c \ drivers/serial_softserial.c \ drivers/sonar_hcsr04.c \ @@ -679,12 +698,41 @@ MOTOLAB_SRC = \ drivers/accgyro_spi_mpu6000.c \ drivers/barometer_ms5611.c \ drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ drivers/serial_usb_vcp.c \ drivers/flash_m25p16.c \ io/flashfs.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ $(VCP_SRC) + +SPRACINGF3MINI_SRC = \ + $(STM32F30x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_bmp280.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/serial_usb_vcp.c \ + drivers/sonar_hcsr04.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + io/transponder_ir.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) +# $(FATFS_SRC) # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h deleted file mode 100644 index 2561a2389..000000000 --- a/src/main/target/CHEBUZZF3/target.h +++ /dev/null @@ -1,127 +0,0 @@ -/* - * 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 "CHF3" // Chebuzz F3 - -#define LED0_GPIO GPIOE -#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12 -#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE -#define LED0_INVERTED -#define LED1_GPIO GPIOE -#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14 -#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE -#define LED1_INVERTED - -#define BEEP_GPIO GPIOE -#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13 -#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE -#define BEEPER_INVERTED - -#define USABLE_TIMER_CHANNEL_COUNT 18 - -#define USE_SPI -#define USE_SPI_DEVICE_1 - -#define GYRO -#define USE_GYRO_L3GD20 -#define USE_GYRO_MPU6050 - -#define L3GD20_SPI SPI1 -#define L3GD20_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOE -#define L3GD20_CS_GPIO GPIOE -#define L3GD20_CS_PIN GPIO_Pin_3 - -#define GYRO_L3GD20_ALIGN CW270_DEG -#define GYRO_MPU6050_ALIGN CW0_DEG - -#define ACC -#define USE_ACC_MPU6050 -#define USE_ACC_LSM303DLHC - -#define ACC_MPU6050_ALIGN CW0_DEG - -#define BARO -#define USE_BARO_MS5611 -#define USE_BARO_BMP280 - -#define MAG -#define USE_MAG_AK8975 - -#define MAG_AK8975_ALIGN CW90_DEG_FLIP - -#define BEEPER -#define LED0 -#define LED1 - -#define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define SERIAL_PORT_COUNT 3 - -#define USE_I2C -#define I2C_DEVICE (I2CDEV_1) - -#define USE_ADC - -#define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 - -#define VBAT_ADC_GPIO GPIOC -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -#define CURRENT_METER_ADC_GPIO GPIOC -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -#define RSSI_ADC_GPIO GPIOC -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_8 - -#define EXTERNAL1_ADC_GPIO GPIOC -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 - -#define GPS -#define LED_STRIP -#if 1 -#define LED_STRIP_TIMER TIM16 -#else -// alternative LED strip configuration, tested working. -#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 -#endif - -#define BLACKBOX -#define GTUNE -#define TELEMETRY -#define SERIAL_RX -#define USE_SERVOS -#define USE_CLI diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h deleted file mode 100644 index 7ebc02d13..000000000 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ /dev/null @@ -1,109 +0,0 @@ -/* - * 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 "SDF3" // STM Discovery F3 - -#define LED0_GPIO GPIOE -#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12 -#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE -#define LED0_INVERTED -#define LED1_GPIO GPIOE -#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14 -#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE -#define LED1_INVERTED - -#define BEEP_GPIO GPIOE -#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13 -#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE -#define BEEPER_INVERTED - - -#define BEEPER_INVERTED - -#define USE_SPI -#define USE_SPI_DEVICE_1 - -#define GYRO -#define USE_GYRO_L3GD20 - -#define L3GD20_SPI SPI1 -#define L3GD20_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOE -#define L3GD20_CS_GPIO GPIOE -#define L3GD20_CS_PIN GPIO_Pin_3 - -#define GYRO_L3GD20_ALIGN CW270_DEG - -#define ACC -#define USE_ACC_LSM303DLHC - -#define MAG -#define USE_MAG_HMC5883 - -#define BEEPER -#define LED0 -#define LED1 - -#define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define SERIAL_PORT_COUNT 3 - -#define USE_I2C -#define I2C_DEVICE (I2CDEV_1) - -#define USE_ADC - -#define ADC_INSTANCE ADC1 -#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 -#define ADC_DMA_CHANNEL DMA1_Channel1 - -#define VBAT_ADC_GPIO GPIOC -#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 -#define VBAT_ADC_CHANNEL ADC_Channel_6 - -#define CURRENT_METER_ADC_GPIO GPIOC -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_7 - -#define RSSI_ADC_GPIO GPIOC -#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 -#define RSSI_ADC_CHANNEL ADC_Channel_8 - -#define EXTERNAL1_ADC_GPIO GPIOC -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9 - -#define BLACKBOX -#define GPS -#define GTUNE -#define LED_STRIP -#define LED_STRIP_TIMER TIM16 -#define TELEMETRY -#define SERIAL_RX -#define USE_SERVOS -#define USE_CLI - -#define USE_SERIAL_1WIRE - -// STM32F3DISCOVERY TX - PD5 connects to UART RX -#define S1W_TX_GPIO GPIOD -#define S1W_TX_PIN GPIO_Pin_5 -// STM32F3DISCOVERY RX - PD6 connects to UART TX -#define S1W_RX_GPIO GPIOD -#define S1W_RX_PIN GPIO_Pin_6