From 66f48801983984593932baeee6be6acbe2e9bbfb Mon Sep 17 00:00:00 2001 From: Michael Keller Date: Tue, 25 Jul 2017 08:26:11 +0800 Subject: [PATCH] Added MATEKF722 board definition. --- src/main/target/MATEKF722/target.c | 40 ++++++++ src/main/target/MATEKF722/target.h | 141 ++++++++++++++++++++++++++++ src/main/target/MATEKF722/target.mk | 6 ++ 3 files changed, 187 insertions(+) create mode 100644 src/main/target/MATEKF722/target.c create mode 100644 src/main/target/MATEKF722/target.h create mode 100644 src/main/target/MATEKF722/target.mk diff --git a/src/main/target/MATEKF722/target.c b/src/main/target/MATEKF722/target.c new file mode 100644 index 000000000..52780f9f6 --- /dev/null +++ b/src/main/target/MATEKF722/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/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PPM DMA1_ST1 + + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S1 DMA1_ST4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // S2 DMA2_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S3 DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S4 DMA2_ST7 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S5 DMA1_ST2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // S6 DMA2_ST6 + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0) // LED STRIP DMA1_ST5 +}; + diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h new file mode 100644 index 000000000..becd4682c --- /dev/null +++ b/src/main/target/MATEKF722/target.h @@ -0,0 +1,141 @@ +/* + * 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 "MKF7" + +#define USBD_PRODUCT_STRING "MatekF7" + +#define LED0_PIN PB9 +#define LED1_PIN PA14 + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define ICM20689_CS_PIN PC2 +#define ICM20689_SPI_INSTANCE SPI1 + +#define USE_EXTI +#define MPU_INT_EXTI PC3 +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO +#define USE_GYRO_SPI_ICM20689 +#define GYRO_ICM20689_ALIGN CW90_DEG + +#define ACC +#define USE_ACC_SPI_ICM20689 +#define ACC_ICM20689_ALIGN CW90_DEG + +// *************** SD Card ************************** +#define USE_SDCARD +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define SDCARD_SPI_INSTANCE SPI3 +#define SDCARD_SPI_CS_PIN PC1 + +// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7 +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 +#define SDCARD_DMA_CHANNEL DMA_CHANNEL_0 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define OSD +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN PB10 +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PB12 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define USE_SOFTSERIAL1 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC1_DMA_STREAM DMA2_Stream0 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC4 +#define RSSI_ADC_PIN PB0 + +#define DEFAULT_FEATURES (FEATURE_OSD ) + +#define LED_STRIP + +#define SPEKTRUM_BIND +#define BIND_PIN PA1 // USART4 RX + +#define USE_ESCSERIAL +#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 8 +#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(5)|TIM_N(8)) diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk new file mode 100644 index 000000000..7ca6032c9 --- /dev/null +++ b/src/main/target/MATEKF722/target.mk @@ -0,0 +1,6 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/max7456.c \ No newline at end of file