From 80f1566af0cfdfeb4ffd5018367cf873bbf653f4 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 11:26:09 +1000 Subject: [PATCH] Added dynamic support for OPBL targets, and also alternate target names that are based on an existing target. --- Makefile | 57 ++++-- .../target/ALIENFLIGHTF1/hardware_revision.c | 111 ----------- .../target/ALIENFLIGHTF1/hardware_revision.h | 30 --- src/main/target/ALIENFLIGHTF1/target.c | 90 --------- src/main/target/ALIENFLIGHTF1/target.h | 188 ------------------ src/main/target/ALIENFLIGHTF1/target.mk | 21 -- src/main/target/CC3D/CC3D_OPBL.mk | 0 src/main/target/NAZE/ALIENFLIGHTF1.mk | 0 src/main/target/REVO/REVO_OPBL.mk | 0 9 files changed, 37 insertions(+), 460 deletions(-) delete mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.c delete mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.h delete mode 100644 src/main/target/ALIENFLIGHTF1/target.c delete mode 100644 src/main/target/ALIENFLIGHTF1/target.h delete mode 100644 src/main/target/ALIENFLIGHTF1/target.mk create mode 100644 src/main/target/CC3D/CC3D_OPBL.mk create mode 100644 src/main/target/NAZE/ALIENFLIGHTF1.mk create mode 100644 src/main/target/REVO/REVO_OPBL.mk diff --git a/Makefile b/Makefile index 0ecfd8498..f0539a31e 100644 --- a/Makefile +++ b/Makefile @@ -59,16 +59,31 @@ HSE_VALUE = 8000000 # used for turning on features like VCP and SDCARD FEATURES = -# silently ignore if the file is not present. Allows for target specific. --include $(ROOT)/src/main/target/$(TARGET)/target.mk - -F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) +ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) +OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) +ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) +BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) +-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk +else +BASE_TARGET := $(TARGET) +endif + +ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET)) +OPBL = yes +endif + +# silently ignore if the file is not present. Allows for target specific. +-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk + +F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) + ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) endif @@ -100,9 +115,9 @@ endif # note that there is no hardfault debugging startup file assembly handler for other platforms ifeq ($(DEBUG_HARDFAULTS),F3) CFLAGS += -DDEBUG_HARDFAULTS -STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S +STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S else -STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S +STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S endif REVISION = $(shell git log -1 --format="%h") @@ -122,7 +137,6 @@ FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') - ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) # F3 TARGETS @@ -304,18 +318,21 @@ TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS) ifeq ($(DEVICE_FLAGS),) DEVICE_FLAGS = -DSTM32F10X_MD endif -DEVICE_FLAGS += -DSTM32F10X +DEVICE_FLAGS += -DSTM32F10X endif # # End F1 targets # - -ifneq ($(FLASH_SIZE),) -DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) +ifneq ($(BASE_TARGET), $(TARGET)) +TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET) endif -TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) +ifneq ($(FLASH_SIZE),) +DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) +endif + +TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) ifeq ($(OPBL),yes) @@ -330,6 +347,8 @@ else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS))) LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld endif .DEFAULT_GOAL := binary +else +.DEFAULT_GOAL := hex endif INCLUDE_DIRS := $(INCLUDE_DIRS) \ @@ -486,7 +505,6 @@ STM32F4xx_COMMON_SRC = \ # check if target.mk supplied ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC) - else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC) else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) @@ -641,10 +659,7 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S ## all : default task; compile C code, build firmware -all: binary - -## all_targets : build all valid target platforms -all_targets: +all: for build_target in $(VALID_TARGETS); do \ echo "" && \ echo "Building $$build_target" && \ @@ -664,7 +679,7 @@ clean_test: cd src/test && $(MAKE) clean || true ## clean_all_targets : clean all valid target platforms -clean_all_targets: +clean_all: for clean_target in $(VALID_TARGETS); do \ echo "" && \ echo "Cleaning $$clean_target" && \ @@ -718,7 +733,9 @@ help: Makefile ## targets : print a list of all valid target platforms (for consumption by scripts) targets: - @echo $(VALID_TARGETS) + @echo "Valid targets: $(VALID_TARGETS)" + @echo "Target: $(TARGET)" + @echo "Base target: $(BASE_TARGET)" ## test : run the cleanflight test suite test: diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.c b/src/main/target/ALIENFLIGHTF1/hardware_revision.c deleted file mode 100644 index dae369844..000000000 --- a/src/main/target/ALIENFLIGHTF1/hardware_revision.c +++ /dev/null @@ -1,111 +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 . - */ - -#include -#include -#include - -#include "platform.h" - -#include "build_config.h" - -#include "drivers/system.h" -#include "drivers/bus_spi.h" -#include "drivers/sensor.h" -#include "drivers/exti.h" -#include "drivers/accgyro.h" -#include "drivers/accgyro_mpu.h" -#include "drivers/accgyro_mpu6500.h" - -#include "hardware_revision.h" - -static const char * const hardwareRevisionNames[] = { - "Unknown", - "Naze 32", - "Naze32 rev.5", - "Naze32 SP" -}; - -uint8_t hardwareRevision = UNKNOWN; - -void detectHardwareRevision(void) -{ - if (hse_value == 8000000) - hardwareRevision = NAZE32; - else if (hse_value == 12000000) - hardwareRevision = NAZE32_REV5; -} - -#ifdef USE_SPI - -#define DISABLE_SPI_CS IOLo(nazeSpiCsPin) -#define ENABLE_SPI_CS IOHi(nazeSpiCsPin) - -#define SPI_DEVICE_NONE (0) -#define SPI_DEVICE_FLASH (1) -#define SPI_DEVICE_MPU (2) - -#define M25P16_INSTRUCTION_RDID 0x9F -#define FLASH_M25P16_ID (0x202015) - -static IO_t nazeSpiCsPin = IO_NONE; - -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; - - // try autodetect flash chip - delay(50); // short delay required after initialisation of SPI device instance. - ENABLE_SPI_CS; - spiTransfer(NAZE_SPI_INSTANCE, in, out, sizeof(out)); - DISABLE_SPI_CS; - - flash_id = in[1] << 16 | in[2] << 8 | in[3]; - if (flash_id == FLASH_M25P16_ID) - return SPI_DEVICE_FLASH; - - - // try autodetect MPU - delay(50); - ENABLE_SPI_CS; - spiTransferByte(NAZE_SPI_INSTANCE, MPU_RA_WHO_AM_I | MPU6500_BIT_RESET); - in[0] = spiTransferByte(NAZE_SPI_INSTANCE, 0xff); - DISABLE_SPI_CS; - - if (in[0] == MPU6500_WHO_AM_I_CONST) - return SPI_DEVICE_MPU; - - return SPI_DEVICE_NONE; -} - -#endif - -void updateHardwareRevision(void) -{ -#ifdef USE_SPI - uint8_t detectedSpiDevice = detectSpiDevice(); - - if (detectedSpiDevice == SPI_DEVICE_MPU && hardwareRevision == NAZE32_REV5) - hardwareRevision = NAZE32_SP; -#endif -} diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.h b/src/main/target/ALIENFLIGHTF1/hardware_revision.h deleted file mode 100644 index 9f663bb6c..000000000 --- a/src/main/target/ALIENFLIGHTF1/hardware_revision.h +++ /dev/null @@ -1,30 +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 . - */ - -typedef enum nazeHardwareRevision_t { - UNKNOWN = 0, - NAZE32, // Naze32 and compatible with 8MHz HSE - NAZE32_REV5, // Naze32 and compatible with 12MHz HSE - NAZE32_SP // Naze32 w/Sensor Platforms -} nazeHardwareRevision_e; - -extern uint8_t hardwareRevision; - -void updateHardwareRevision(void); -void detectHardwareRevision(void); - -void spiBusInit(void); diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c deleted file mode 100644 index be1c6ff53..000000000 --- a/src/main/target/ALIENFLIGHTF1/target.c +++ /dev/null @@ -1,90 +0,0 @@ - -#include -#include - -#include -#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), - 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), // 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 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 - 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), // 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 - 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), // servo #4 - 0xFFFF -}; - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 -}; - diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h deleted file mode 100644 index 52048887f..000000000 --- a/src/main/target/ALIENFLIGHTF1/target.h +++ /dev/null @@ -1,188 +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 "AFF1" // AlienFlight F1. -#define ALIENFLIGHT -#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP) -#define USE_HARDWARE_REVISION_DETECTION - -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) - -#define BEEPER PA12 // PA12 (Beeper) - -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_PIN PC14 - -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 - -#define USE_EXTI - -// SPI2 -// PB15 28 SPI2_MOSI -// PB14 27 SPI2_MISO -// PB13 26 SPI2_SCK -// PB12 25 SPI2_NSS - -#define USE_SPI -#define USE_SPI_DEVICE_2 - -#define NAZE_SPI_INSTANCE SPI2 -#define NAZE_SPI_CS_GPIO GPIOB -#define NAZE_SPI_CS_PIN PB12 -#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB - -// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO -#define M25P16_CS_PIN NAZE_SPI_CS_PIN -#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE - -#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL -#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO -#define MPU6500_CS_PIN NAZE_SPI_CS_PIN -#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE - - -#define USE_FLASHFS - -#define USE_FLASH_M25P16 - -#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC - -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL - -//#define DEBUG_MAG_DATA_READY_INTERRUPT -#define USE_MAG_DATA_READY_SIGNAL - -#define GYRO -#define USE_GYRO_MPU3050 -#define USE_GYRO_MPU6050 -#define USE_GYRO_MPU6500 -#define USE_GYRO_SPI_MPU6500 - - -#define GYRO_MPU3050_ALIGN CW0_DEG -#define GYRO_MPU6050_ALIGN CW0_DEG -#define GYRO_MPU6500_ALIGN CW0_DEG - -#define ACC -#define USE_ACC_ADXL345 -#define USE_ACC_BMA280 -#define USE_ACC_MMA8452 -#define USE_ACC_MPU6050 -#define USE_ACC_MPU6500 -#define USE_ACC_SPI_MPU6500 - -#define ACC_ADXL345_ALIGN CW270_DEG -#define ACC_MPU6050_ALIGN CW0_DEG -#define ACC_MMA8452_ALIGN CW90_DEG -#define ACC_BMA280_ALIGN CW0_DEG -#define ACC_MPU6500_ALIGN CW0_DEG - -#define BARO -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 - -#define MAG -#define USE_MAG_HMC5883 - -#define MAG_HMC5883_ALIGN CW180_DEG - -#define SONAR -#define DISPLAY - -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 -#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 SOFTSERIAL_2_TIMER TIM3 -#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 -#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 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_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 - - -#define LED_STRIP -#define LED_STRIP_TIMER TIM3 -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER - -#undef GPS - -#define SPEKTRUM_BIND -// USART2, PA3 -#define BIND_PIN PA3 -#define BINDPLUG_PIN PB5 - -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -// alternative defaults for AlienFlight F1 target - -#define HARDWARE_BIND_PLUG - -// IO - assuming all IOs on 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) - - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) - -#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) -#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB) - diff --git a/src/main/target/ALIENFLIGHTF1/target.mk b/src/main/target/ALIENFLIGHTF1/target.mk deleted file mode 100644 index a73a30ea5..000000000 --- a/src/main/target/ALIENFLIGHTF1/target.mk +++ /dev/null @@ -1,21 +0,0 @@ -FEATURES = ONBOARDFLASH HIGHEND -F1_TARGETS += $(TARGET) - -TARGET_SRC = \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - hardware_revision.c \ No newline at end of file diff --git a/src/main/target/CC3D/CC3D_OPBL.mk b/src/main/target/CC3D/CC3D_OPBL.mk new file mode 100644 index 000000000..e69de29bb diff --git a/src/main/target/NAZE/ALIENFLIGHTF1.mk b/src/main/target/NAZE/ALIENFLIGHTF1.mk new file mode 100644 index 000000000..e69de29bb diff --git a/src/main/target/REVO/REVO_OPBL.mk b/src/main/target/REVO/REVO_OPBL.mk new file mode 100644 index 000000000..e69de29bb