From 47f4d815a2ae18cafa71792aa8910d3d40077dff Mon Sep 17 00:00:00 2001 From: flyinglemonfpv Date: Fri, 17 Mar 2017 11:52:13 +0100 Subject: [PATCH] Removed PLUMF4 as separate target, added PLUMF4 variant to KIWIF4. --- src/main/target/KIWIF4/PLUMF4.mk | 0 src/main/target/KIWIF4/target.c | 4 + src/main/target/KIWIF4/target.h | 20 ++++- src/main/target/PLUMF4/README.md | 14 ---- src/main/target/PLUMF4/target.c | 33 --------- src/main/target/PLUMF4/target.h | 122 ------------------------------- src/main/target/PLUMF4/target.mk | 5 -- 7 files changed, 22 insertions(+), 176 deletions(-) create mode 100644 src/main/target/KIWIF4/PLUMF4.mk delete mode 100644 src/main/target/PLUMF4/README.md delete mode 100644 src/main/target/PLUMF4/target.c delete mode 100644 src/main/target/PLUMF4/target.h delete mode 100644 src/main/target/PLUMF4/target.mk diff --git a/src/main/target/KIWIF4/PLUMF4.mk b/src/main/target/KIWIF4/PLUMF4.mk new file mode 100644 index 000000000..e69de29bb diff --git a/src/main/target/KIWIF4/target.c b/src/main/target/KIWIF4/target.c index add381e33..896cbfd7d 100644 --- a/src/main/target/KIWIF4/target.c +++ b/src/main/target/KIWIF4/target.c @@ -29,5 +29,9 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), +#ifdef PLUMF4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), //LED +#else DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED +#endif }; diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index 445749323..91df8e07a 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -17,13 +17,26 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "KIWI" +#ifdef PLUMF4 +#define TARGET_BOARD_IDENTIFIER "PLUM" +#define USBD_PRODUCT_STRING "PLUMF4" +#else + +#define TARGET_BOARD_IDENTIFIER "KIWI" #define USBD_PRODUCT_STRING "KIWIF4" +#endif + +#ifdef PLUMF4 +#define LED0 PB4 + +#else + #define LED0 PB5 #define LED1 PB4 +#endif #define BEEPER PA8 @@ -47,6 +60,7 @@ #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG +#ifdef KIWIF4 #define OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI2 @@ -54,7 +68,7 @@ //#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5 //#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0 //#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER - +#endif #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -92,11 +106,13 @@ #define USE_SPI_DEVICE_1 +#ifdef KIWIF4 #define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 +#endif #define USE_SPI_DEVICE_3 #define SPI3_NSS_PIN PA15 diff --git a/src/main/target/PLUMF4/README.md b/src/main/target/PLUMF4/README.md deleted file mode 100644 index bb9eef86d..000000000 --- a/src/main/target/PLUMF4/README.md +++ /dev/null @@ -1,14 +0,0 @@ -##PLUM F4 - -Available at: flyinglemon.eu - -###Board information: - -- CPU - STM32F405RGT6 -- MPU6000 SPI gyro -- SPI Flash -- Build in 5V BEC board can be powered from main battery (up to 6S) -- RC input: S.BUS with HW inverter, Spektrum -- Other connectors: RSSI, Current sensor, LED strip, Buzzer -- Size: 36mm x 36mm - diff --git a/src/main/target/PLUMF4/target.c b/src/main/target/PLUMF4/target.c deleted file mode 100644 index bab35ecb4..000000000 --- a/src/main/target/PLUMF4/target.c +++ /dev/null @@ -1,33 +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 "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), -}; diff --git a/src/main/target/PLUMF4/target.h b/src/main/target/PLUMF4/target.h deleted file mode 100644 index 4ba227af6..000000000 --- a/src/main/target/PLUMF4/target.h +++ /dev/null @@ -1,122 +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 "PLUM" -#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) - -#define USBD_PRODUCT_STRING "PLUMF4" - -#define LED0 PB4 - -#define BEEPER PA8 - -#define INVERTER_PIN_USART1 PC0 // PC0 used as inverter select GPIO - -// MPU6000 interrupts -#define USE_EXTI -#define MPU_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 - -#define GYRO - -#define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG - -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG - -#define USE_FLASHFS -#define USE_FLASH_M25P16 -#define M25P16_CS_PIN SPI3_NSS_PIN -#define M25P16_SPI_INSTANCE SPI3 - -#define USE_VCP -#define VBUS_SENSING_PIN PC5 -#define VBUS_SENSING_ENABLED - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 - -#define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1 - -#define USE_DSHOT - -#define USE_SPI - -#define USE_SPI_DEVICE_1 - -#define USE_SPI_DEVICE_2 -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define USE_SPI_DEVICE_3 -#define SPI3_NSS_PIN PA15 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PC12 - - -#define USE_ADC -#define BOARD_HAS_VOLTAGE_DIVIDER -#define VBAT_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define CURRENT_METER_ADC_PIN PC3 - -#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX) -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS - -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - -#define LED_STRIP - -#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 (BIT(2)) - -#define USABLE_TIMER_CHANNEL_COUNT 12 - -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) ) - -#define CMS -#define USE_MSP_DISPLAYPORT - diff --git a/src/main/target/PLUMF4/target.mk b/src/main/target/PLUMF4/target.mk deleted file mode 100644 index f9414a866..000000000 --- a/src/main/target/PLUMF4/target.mk +++ /dev/null @@ -1,5 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro_spi_mpu6000.c