diff --git a/src/main/target/FF_FORTINIF4/README.md b/src/main/target/FF_FORTINIF4/README.md new file mode 100644 index 0000000000..902b834a98 --- /dev/null +++ b/src/main/target/FF_FORTINIF4/README.md @@ -0,0 +1,22 @@ +# FuriousFPV FortiniF4 + +available at: http://furiousfpv.com + +# Features: + +- Ultra Simplified OSD Interface w/ No PC Necessary +- High Performance, Low Noise, Ultra Sensitive 32kHz Invensense 20602 Gyro +- Five UARTS for Simultaneous Connections of SBUS, S.Port, MSP Receiver, and USB +- UARTS Connection Options for TBS Smart Audio or Immersion RC Tramp +- Integrated Soft Mount Silicone Damping for Maximum FC Functionality +- Inrush Voltage Protection Input & Output via Transient Voltage Suppressor +- High Quality 5V 2A BEC w/ 2S - 6S Voltage Input Range +- Built In Driver Inverter for SBUS and Smart Port Connection +- Separate Power Supply for Gyro w/ LDO for Low Noise & High Accuracy +- 3.3V - 5V Selectable BEC Output for Rx +- Fully Capable to Power Rx via USB Port +- Clean and Easy to Connect 4-in-1 ESC +- Clean and easy to connect VTX have telemetry (Stealth race, Tramp, Unify) +- Additional Serial RX 5 & Optional UART6 (Tx6 with/without inversion)* +- Weight: 5.5g +- Size: 36x36mm diff --git a/src/main/target/FF_FORTINIF4/config.c b/src/main/target/FF_FORTINIF4/config.c new file mode 100644 index 0000000000..439e2cf1eb --- /dev/null +++ b/src/main/target/FF_FORTINIF4/config.c @@ -0,0 +1,40 @@ +/* + * 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 + +#ifdef TARGET_CONFIG +#include "fc/config.h" + +#include "config/feature.h" + +#include "rx/rx.h" + +#include "hardware_revision.h" + +void targetConfiguration(void) +{ + if (hardwareRevision == FORTINIF4_REV_2) { + featureSet(FEATURE_OSD); + } + + rxConfigMutable()->halfDuplex = false; +} +#endif diff --git a/src/main/target/FF_FORTINIF4/hardware_revision.c b/src/main/target/FF_FORTINIF4/hardware_revision.c new file mode 100644 index 0000000000..ce6c05648d --- /dev/null +++ b/src/main/target/FF_FORTINIF4/hardware_revision.c @@ -0,0 +1,53 @@ +/* + * 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/build_config.h" + +#include "drivers/io.h" +#include "drivers/time.h" + +#include "hardware_revision.h" + +uint8_t hardwareRevision = FORTINIF4_UNKNOWN; + +static IO_t HWDetectPin = IO_NONE; + +void detectHardwareRevision(void) +{ + HWDetectPin = IOGetByTag(IO_TAG(HW_PIN)); + IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0); + IOConfigGPIO(HWDetectPin, IOCFG_IPU); + + delayMicroseconds(10); // allow configuration to settle + + // Check hardware revision + if (IORead(HWDetectPin)) { + hardwareRevision = FORTINIF4_REV_1; + } else { + hardwareRevision = FORTINIF4_REV_2; + } +} + +void updateHardwareRevision(void) +{ +} diff --git a/src/main/target/FF_FORTINIF4/hardware_revision.h b/src/main/target/FF_FORTINIF4/hardware_revision.h new file mode 100644 index 0000000000..7362d32feb --- /dev/null +++ b/src/main/target/FF_FORTINIF4/hardware_revision.h @@ -0,0 +1,28 @@ +/* + * 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 + +typedef enum ftf4HardwareRevision_t { + FORTINIF4_UNKNOWN = 0, + FORTINIF4_REV_1, // SPI Flash + FORTINIF4_REV_2 // OSD +} ftf4HardwareRevision_e; + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); diff --git a/src/main/target/FF_FORTINIF4/target.c b/src/main/target/FF_FORTINIF4/target.c new file mode 100644 index 0000000000..cd1ccf81b0 --- /dev/null +++ b/src/main/target/FF_FORTINIF4/target.c @@ -0,0 +1,40 @@ +/* + * 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/pwm_mapping.h" +#include "drivers/timer.h" + +#define TIM_EN TIMER_OUTPUT_ENABLED + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_EN, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_EN, IOCFG_AF_PP, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S2_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_EN, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S3_OUT + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_EN, IOCFG_AF_PP, GPIO_AF_TIM2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S4_OUT + { TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_PPM | TIM_USE_MC_CHNFW }, // PPM IN + { TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_LED | TIM_USE_MC_CHNFW }, // LED +// DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0 ), // S1_OUT - DMA1_ST7 +// DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0 ), // S2_OUT - DMA1_ST2 +// DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 1 ), // S3_OUT - DMA1_ST6 +// DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0 ), // S4_OUT - DMA1_ST1 +// DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN +// DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // LED - DMA1_ST3 +}; diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h new file mode 100644 index 0000000000..db7965894b --- /dev/null +++ b/src/main/target/FF_FORTINIF4/target.h @@ -0,0 +1,167 @@ +/* + * 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 "FORT" +#define USBD_PRODUCT_STRING "FortiniF4" +#define TARGET_CONFIG +#define USE_HARDWARE_REVISION_DETECTION +#define HW_PIN PC14 +/*--------------LED----------------*/ +#define LED0 PB5 +#define LED1 PB6 +/*---------------------------------*/ + +/*------------BEEPER---------------*/ +#define BEEPER PB4 +#define BEEPER_INVERTED +/*---------------------------------*/ + +/*----------CAMERA CONTROL---------*/ +//#define CAMERA_CONTROL_PIN PB7 +/*---------------------------------*/ + +/*------------SENSORS--------------*/ +// MPU interrupt +#define USE_EXTI +#define MPU_INT_EXTI PC4 +//#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define MPU6500_CS_PIN PA8 +#define MPU6500_SPI_BUS BUS_SPI1 + +#define USE_GYRO +#define USE_GYRO_MPU6500 +#define GYRO_MPU6500_ALIGN CW180_DEG + +#define USE_ACC +#define USE_ACC_MPU6500 +#define ACC_MPU6500_ALIGN CW180_DEG +/*---------------------------------*/ + +/*------------FLASH----------------*/ +#define M25P16_CS_PIN PB3 +#define M25P16_SPI_BUS BUS_SPI3 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +/*---------------------------------*/ + +/*-------------OSD-----------------*/ +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI3 +#define MAX7456_CS_PIN PB3 +//#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz +//#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) +/*---------------------------------*/ + +/*-----------USB-UARTs-------------*/ +#define USB_IO +#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 USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 +#define INVERTER_PIN_UART3 PC15 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN NONE + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 6 + +#define CMS +#define USE_MSP_DISPLAYPORT +/*---------------------------------*/ + +/*-------------SPIs----------------*/ +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA8 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PB3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 +/*---------------------------------*/ + +/*-------------ADCs----------------*/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +/*---------------------------------*/ + +/*-----------LED Strip-------------*/ +#define LED_STRIP +#define WS2811_PIN PB7 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream2 +#define WS2811_DMA_CHANNEL DMA_Channel_3 +/*---------------------------------*/ + +/*-------------ESCs----------------*/ +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define USE_ESCSERIAL +#define ESCSERIAL_TIMER_TX_PIN PB0 // (HARDARE=0) +/*---------------------------------*/ + +/*--------DEFAULT VALUES-----------*/ +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +/*---------------------------------*/ + +/*--------SPEKTRUM BIND---------.--*/ +#define SPEKTRUM_BIND +#define BIND_PIN UART3_RX_PIN +/*---------------------------------*/ + +/*--------------TIMERS-------------*/ +#define MAX_PWM_OUTPUT_PORTS 6 +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) ) +/*---------------------------------*/ diff --git a/src/main/target/FF_FORTINIF4/target.mk b/src/main/target/FF_FORTINIF4/target.mk new file mode 100644 index 0000000000..a6b838a95e --- /dev/null +++ b/src/main/target/FF_FORTINIF4/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/max7456.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stdperiph.c