diff --git a/src/main/target/FLYWOOF405/config.c b/src/main/target/FLYWOOF405/config.c deleted file mode 100755 index b0e7abf40b..0000000000 --- a/src/main/target/FLYWOOF405/config.c +++ /dev/null @@ -1,64 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" -#include "io/serial.h" -#include "pg/bus_spi.h" -#include "rx/rx.h" -#include "telemetry/telemetry.h" - -#define TELEMETRY_UART SERIAL_PORT_USART1 - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { TELEMETRY_UART, FUNCTION_TELEMETRY_SMARTPORT }, -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - telemetryConfigMutable()->halfDuplex = 0; - telemetryConfigMutable()->telemetry_inverted = true; - - // Register MAX7456 CS pin as OPU - - // Invalidate IPU entry first - for (int i = 0 ; i < SPI_PREINIT_IPU_COUNT ; i++) { - if (spiPreinitIPUConfig(i)->csnTag == IO_TAG(MAX7456_SPI_CS_PIN)) { - spiPreinitIPUConfigMutable(i)->csnTag = IO_TAG(NONE); - break; - } - } - - // Add as OPU entry - for (int i = 0 ; i < SPI_PREINIT_OPU_COUNT ; i++) { - if (spiPreinitOPUConfig(i)->csnTag == IO_TAG(NONE)) { - spiPreinitOPUConfigMutable(i)->csnTag = IO_TAG(MAX7456_SPI_CS_PIN); - break; - } - } -} -#endif diff --git a/src/main/target/FLYWOOF405/target.c b/src/main/target/FLYWOOF405/target.c deleted file mode 100755 index d2540cea93..0000000000 --- a/src/main/target/FLYWOOF405/target.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#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(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2_OUT - DMA1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // S3_OUT - DMA1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // S4_OUT - DMA1_ST1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S5_OUT - DMA1_ST5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // S6_OUT - DMA1_ST3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S7_OUT - DMA2_ST7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S8_OUT - DMA1_ST4 - - DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 - - DEF_TIM(TIM1, CH2, PA9, TIM_USE_PWM, 0, 0), // FC CAM -}; diff --git a/src/main/target/FLYWOOF405/target.h b/src/main/target/FLYWOOF405/target.h deleted file mode 100755 index 995376c383..0000000000 --- a/src/main/target/FLYWOOF405/target.h +++ /dev/null @@ -1,165 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software 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 and Betaflight are distributed in the hope that they - * 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 this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "FWF4" -#define USBD_PRODUCT_STRING "FLYWOOF405" - -#define USE_TARGET_CONFIG - -#define LED0_PIN PC14///////////// - -#define USE_BEEPER -#define BEEPER_PIN PC13///////////// -#define BEEPER_INVERTED -#define INVERTER_PIN_UART3 PB15 - -//define camera control -#define CAMERA_CONTROL_PIN PA9//////////// - - - -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - -#define USE_SPI - -#define USE_SPI_DEVICE_1 //ICM20689-MPU6000 -#define SPI1_NSS_PIN PC4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - - - -#define USE_GYRO -#define USE_ACC -//------ICM20689 -#define ICM20689_CS_PIN PC4 -#define ICM20689_SPI_INSTANCE SPI1 - -#define USE_GYRO_SPI_ICM20689 -#define GYRO_ICM20689_ALIGN CW270_DEG - -#define USE_ACC_SPI_ICM20689 -#define ACC_ICM20689_ALIGN CW270_DEG -//------MPU6000 -#define MPU6000_CS_PIN PC4 -#define MPU6000_SPI_INSTANCE SPI1 - -#define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG - -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG - -//Baro & MAG------------------------------- -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C_DEVICE (I2CDEV_1) -#define I2C1_SCL PB6 // SCL pad -#define I2C1_SDA PB9 // SDA pad -#define BARO_I2C_INSTANCE I2C_DEVICE -#define MAG_I2C_INSTANCE I2C_DEVICE - -#define USE_MAG -#define USE_MAG_HMC5883 //External, connect to I2C1 -#define USE_MAG_QMC5883 -#define MAG_HMC5883_ALIGN CW180_DEG - -#define USE_BARO -#define USE_BARO_MS5611 //External, connect to I2C1 -#define USE_BARO_BMP280 //onboard - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI3 -#define MAX7456_SPI_CS_PIN PB14 -#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) -#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) - -#define USE_FLASHFS -#define USE_FLASH_M25P16 -#define FLASH_CS_PIN PB3 -#define FLASH_SPI_INSTANCE SPI3 - -#define USE_VCP -#define USB_DETECT_PIN PA8 -#define USE_USB_DETECT - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PB6 //SCL/UART1_TX/TIM4_CH1 -#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 USE_UART4 // Uart4 can be used for GPS or RunCam Split -#define UART4_RX_PIN PA1 -#define UART4_TX_PIN PA0 - -#define USE_UART5 //Uart5 can be used for ESC sensor -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN NONE - -#define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 7 //vcp, uart1, uart3, uart4, uart5, uart6, softSerial1 - - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PB8 // (HARDARE=0,PPM) - - - -#define USE_SPI_DEVICE_3 //dataflash -#define SPI3_NSS_PIN PB3 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PC12 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define USE_ADC -#define ADC1_DMA_STREAM DMA2_Stream0 -#define VBAT_ADC_PIN PC3 -#define CURRENT_METER_ADC_PIN PC2 -#define RSSI_ADC_PIN PC1 - -#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_OSD ) -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART3 - -#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 11 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4)| TIM_N(8)) - diff --git a/src/main/target/FLYWOOF405/target.mk b/src/main/target/FLYWOOF405/target.mk deleted file mode 100755 index f29ea9ab28..0000000000 --- a/src/main/target/FLYWOOF405/target.mk +++ /dev/null @@ -1,12 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_icm20689.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/max7456.c diff --git a/src/main/target/KAKUTEF4/FLYWOOF405.mk b/src/main/target/KAKUTEF4/FLYWOOF405.mk new file mode 100755 index 0000000000..3f0326b281 --- /dev/null +++ b/src/main/target/KAKUTEF4/FLYWOOF405.mk @@ -0,0 +1 @@ +#FLYWOOF405.mk file diff --git a/src/main/target/KAKUTEF4/target.c b/src/main/target/KAKUTEF4/target.c index 6398017150..1715709dc5 100644 --- a/src/main/target/KAKUTEF4/target.c +++ b/src/main/target/KAKUTEF4/target.c @@ -27,13 +27,30 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + + #if defined(FLYWOOF405) + DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM IN + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2_OUT - DMA1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // S3_OUT - DMA1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S5_OUT - DMA1_ST5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // S6_OUT - DMA1_ST3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S7_OUT - DMA2_ST7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S8_OUT - DMA1_ST4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 + #else DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1_OUT - DMA1_ST7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2_OUT - DMA1_ST2 DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // S3_OUT - DMA1_ST6 DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // S4_OUT - DMA1_ST1 - #if defined(KAKUTEF4V2) + #endif + + #if defined(KAKUTEF4V2) DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 + #elif defined(FLYWOOF405) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_PWM, 0, 0), // FC CAM #else DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0), // S5_OUT - DMA1_ST2 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // S6_OUT - DMA2_ST4 diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index 78e13e9fae..59dabf4c86 100644 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -22,6 +22,9 @@ #if defined(KAKUTEF4V2) #define TARGET_BOARD_IDENTIFIER "KTV2" #define USBD_PRODUCT_STRING "KakuteF4-V2" +#elif defined(FLYWOOF405) +#define TARGET_BOARD_IDENTIFIER "FWF4" +#define USBD_PRODUCT_STRING "FLYWOOF405" #else #define TARGET_BOARD_IDENTIFIER "KTV1" #define USBD_PRODUCT_STRING "KakuteF4-V1" @@ -29,12 +32,25 @@ #define USE_TARGET_CONFIG +#if defined(FLYWOOF405) +#define LED0_PIN PC14 +#else #define LED0_PIN PB5 #define LED1_PIN PB4 #define LED2_PIN PB6 +#endif + #define USE_BEEPER + +#if defined(FLYWOOF405) +//define camera control +#define CAMERA_CONTROL_PIN PA9 +#define BEEPER_PIN PC13 +#else #define BEEPER_PIN PC9 +#endif + #define BEEPER_INVERTED #define INVERTER_PIN_UART3 PB15 @@ -56,11 +72,27 @@ #define USE_GYRO_SPI_ICM20689 #define GYRO_ICM20689_ALIGN CW270_DEG -#ifdef KAKUTEF4V2 // There is invertor on RXD3(PB11), so PB10/PB11 can't be used as I2C2. +#if defined(FLYWOOF405) +//------MPU6000 +#define MPU6000_CS_PIN PC4 +#define MPU6000_SPI_INSTANCE SPI1 +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW270_DEG +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW270_DEG +#endif + +#if defined(KAKUTEF4V2) || defined(FLYWOOF405) // There is invertor on RXD3(PB11), so PB10/PB11 can't be used as I2C2. #define USE_I2C //No other I2C pins are fanned out, So V1 don't support I2C peripherals. #define USE_I2C_DEVICE_1 #define I2C_DEVICE (I2CDEV_1) + +#if defined(FLYWOOF405) +#define I2C1_SCL PB6 +#else #define I2C1_SCL PB8 // SCL pad +#endif + #define I2C1_SDA PB9 // SDA pad #define BARO_I2C_INSTANCE I2C_DEVICE #define MAG_I2C_INSTANCE I2C_DEVICE @@ -80,7 +112,6 @@ #define MAX7456_SPI_CS_PIN PB14 #define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) #define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) - #define FLASH_CS_PIN PB3 #define FLASH_SPI_INSTANCE SPI3 @@ -93,7 +124,13 @@ #define USE_UART1 #define UART1_RX_PIN PA10 + +#if defined (FLYWOOF405) +#define UART1_TX_PIN PB6 //SCL/UART1_TX/TIM4_CH1 +#else #define UART1_TX_PIN PA9 +#endif + #define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define USE_UART3 @@ -104,7 +141,7 @@ #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 -#ifdef KAKUTEF4V2 // Uart4 and Uart5 are fanned out on v2 +#if defined (KAKUTEF4V2) || defined(FLYWOOF405) // Uart4 and Uart5 are fanned out on v2 #define USE_UART4 // Uart4 can be used for GPS or RunCam Split #define UART4_RX_PIN PA1 #define UART4_TX_PIN PA0 @@ -122,10 +159,14 @@ #endif #define USE_ESCSERIAL + +#if defined(FLYWOOF405) +#define ESCSERIAL_TIMER_TX_PIN PB8 +#else #define ESCSERIAL_TIMER_TX_PIN PC7 // (HARDARE=0,PPM) - +#endif + #define USE_SPI - #define USE_SPI_DEVICE_1 //ICM20689 #define SPI1_NSS_PIN PC4 #define SPI1_SCK_PIN PA5 @@ -157,9 +198,12 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#ifdef KAKUTEF4V2 +#if defined (KAKUTEF4V2) #define USABLE_TIMER_CHANNEL_COUNT 6 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8)) +#elif defined(FLYWOOF405) +#define USABLE_TIMER_CHANNEL_COUNT 11 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4)| TIM_N(8)) #else #define USABLE_TIMER_CHANNEL_COUNT 8 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8)) diff --git a/src/main/target/KAKUTEF4/target.mk b/src/main/target/KAKUTEF4/target.mk index 8f2f2e7348..017defb8d2 100644 --- a/src/main/target/KAKUTEF4/target.mk +++ b/src/main/target/KAKUTEF4/target.mk @@ -9,3 +9,7 @@ TARGET_SRC = \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/max7456.c + +ifeq ($(TARGET), FLYWOOF405) +TARGET_SRC += drivers/accgyro/accgyro_spi_mpu6000.c +endif