mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
change CLRACINGF7 target to use DMAR burst
change CLRACINGF7 to one timer and flash chip test flash Update CLRACINGF7 TARGET update the file copyright
This commit is contained in:
parent
a3b67d77b0
commit
d79fbf2938
5 changed files with 49 additions and 59 deletions
|
@ -1,6 +1,6 @@
|
||||||
|
|
||||||
F405_TARGETS += $(TARGET)
|
F405_TARGETS += $(TARGET)
|
||||||
FEATURES += VCP ONBOARDFLASH
|
FEATURES += VCP ONBOARDFLASH SDCARD
|
||||||
|
|
||||||
TARGET_SRC = \
|
TARGET_SRC = \
|
||||||
drivers/accgyro/accgyro_mpu.c \
|
drivers/accgyro/accgyro_mpu.c \
|
||||||
|
|
|
@ -1,9 +1,9 @@
|
||||||
MCU: STM32F722RE
|
MCU: STM32F722RE
|
||||||
IMU: MPU-6000
|
IMU: ICM-20602
|
||||||
IMU Interrupt: yes
|
IMU Interrupt: yes
|
||||||
BARO: NO
|
BARO: NO
|
||||||
VCP: YES
|
VCP: YES
|
||||||
Hardware UARTS:
|
Hardware UARTS: 6 uarts
|
||||||
OSD: uses a AB7456 chip
|
OSD: uses a AB7456 chip
|
||||||
Blackbox: SD Card
|
Blackbox: SD Card
|
||||||
PPM/UART NOT Shared: YES
|
PPM/UART NOT Shared: YES
|
||||||
|
|
|
@ -17,7 +17,6 @@
|
||||||
*
|
*
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
@ -27,20 +26,16 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "drivers/timer_def.h"
|
||||||
|
|
||||||
// DSHOT will work for motor 1-6.
|
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
DEF_TIM(TIM10, CH1, PB8, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
|
DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
|
||||||
|
|
||||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // PWM1 - DMA1_ST6 D(1, 7, 3),D(1, 6, 3)
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST6
|
||||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), // PWM2 - DMA2_ST2 D(2, 4, 7),D(2, 2, 0)
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST6
|
||||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), // PWM3 - DMA1_ST1 D(1, 1, 3)
|
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST6
|
||||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // PWM4 - DMA1_ST2 D(1, 2, 5)
|
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // D1-ST6
|
||||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 2), // PWM5 - DMA2_ST3 D(2, 6, 0),D(2, 1, 6),D(2, 3, 6)
|
|
||||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // PWM6 - DMA1_ST0 D(1, 0, 2)
|
|
||||||
|
|
||||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S5_OUT - DMA2_ST6 D(2, 6, 0),D(2, 6, 6)
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -20,32 +20,21 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
#define TARGET_BOARD_IDENTIFIER "CLR7"
|
#define TARGET_BOARD_IDENTIFIER "CLR7"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
#define USBD_PRODUCT_STRING "CLRACINGF7"
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
#define LED0_PIN PB0
|
#define LED0_PIN PB0
|
||||||
#define USE_BEEPER
|
#define USE_BEEPER
|
||||||
#define BEEPER_PIN PB4
|
#define BEEPER_PIN PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
//define camera control
|
//define camera control
|
||||||
#define CAMERA_CONTROL_PIN PB8
|
#define CAMERA_CONTROL_PIN PB3
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MPU_INT_EXTI PC4
|
#define MPU_INT_EXTI PC4
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
//ICM20689
|
|
||||||
#define ICM20689_CS_PIN PA4
|
|
||||||
#define ICM20689_SPI_INSTANCE SPI1
|
|
||||||
#define USE_GYRO
|
|
||||||
#define USE_GYRO_SPI_ICM20689
|
|
||||||
#define GYRO_ICM20689_ALIGN CW0_DEG
|
|
||||||
#define USE_ACC
|
|
||||||
#define USE_ACC_SPI_ICM20689
|
|
||||||
#define ACC_ICM20689_ALIGN CW0_DEG
|
|
||||||
|
|
||||||
//MPU-6000
|
//MPU-6000
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
@ -73,24 +62,33 @@
|
||||||
#define MAX7456_SPI_CS_PIN PA15
|
#define MAX7456_SPI_CS_PIN PA15
|
||||||
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
|
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
|
||||||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||||
|
//define use flash
|
||||||
|
#define FLASH_CS_PIN PB12
|
||||||
|
#define FLASH_SPI_INSTANCE SPI2
|
||||||
|
#define USE_FLASHFS
|
||||||
|
#define USE_FLASH_M25P16
|
||||||
|
//define use SD card
|
||||||
|
|
||||||
#define USE_SDCARD
|
#define USE_SDCARD
|
||||||
#define SDCARD_DETECT_PIN PB7
|
#define SDCARD_DETECT_PIN PA8
|
||||||
#define SDCARD_SPI_INSTANCE SPI2
|
#define SDCARD_SPI_INSTANCE SPI2
|
||||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
|
|
||||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||||
// Divide to under 25MHz for normal operation:
|
// Divide to under 25MHz for normal operation:
|
||||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||||
|
|
||||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
|
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
|
||||||
#define SDCARD_DMA_CHANNEL 0
|
#define SDCARD_DMA_CHANNEL 0
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
||||||
#define USE_UART1
|
#define USE_UART1
|
||||||
#define UART1_RX_PIN PA10
|
#define UART1_RX_PIN PA10
|
||||||
#define UART1_TX_PIN PA9
|
#define UART1_TX_PIN PA9
|
||||||
|
|
||||||
|
#define USE_UART2
|
||||||
|
#define UART2_RX_PIN PA3
|
||||||
|
#define UART2_TX_PIN PA2
|
||||||
|
|
||||||
#define USE_UART3
|
#define USE_UART3
|
||||||
#define UART3_RX_PIN PB11
|
#define UART3_RX_PIN PB11
|
||||||
#define UART3_TX_PIN PB10
|
#define UART3_TX_PIN PB10
|
||||||
|
@ -99,39 +97,39 @@
|
||||||
#define UART4_RX_PIN PA1
|
#define UART4_RX_PIN PA1
|
||||||
#define UART4_TX_PIN PA0
|
#define UART4_TX_PIN PA0
|
||||||
|
|
||||||
|
#define USE_UART5
|
||||||
|
#define UART5_RX_PIN PD2
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
|
||||||
#define USE_UART6
|
#define USE_UART6
|
||||||
#define UART6_RX_PIN PC7
|
#define UART6_RX_PIN PC7
|
||||||
#define UART6_TX_PIN PC6
|
#define UART6_TX_PIN PC6
|
||||||
|
|
||||||
#define USE_SOFTSERIAL1
|
//#define USE_SOFTSERIAL1
|
||||||
|
#define SERIAL_PORT_COUNT 7 //VCP, USART1, USART2,USART3,USART4,USART5,USART6
|
||||||
#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3,USART4, USART6, SOFT_SERIAL1
|
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PB8 // (Hardware=0, PPM)
|
#define ESCSERIAL_TIMER_TX_PIN PB8 // (Hardware=0, PPM)
|
||||||
|
|
||||||
// XXX To target maintainer: Bus device to configure must be specified.
|
|
||||||
//#define USE_I2C
|
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
#define USE_SPI_DEVICE_3
|
#define USE_SPI_DEVICE_3
|
||||||
|
|
||||||
#define SPI1_NSS_PIN PA4
|
#define SPI1_NSS_PIN PA4
|
||||||
#define SPI1_SCK_PIN PA5
|
#define SPI1_SCK_PIN PA5
|
||||||
#define SPI1_MISO_PIN PA6
|
#define SPI1_MISO_PIN PA6
|
||||||
#define SPI1_MOSI_PIN PA7
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
#define SPI2_NSS_PIN PB12
|
#define SPI2_NSS_PIN PB12
|
||||||
#define SPI2_SCK_PIN PB13
|
#define SPI2_SCK_PIN PB13
|
||||||
#define SPI2_MISO_PIN PB14
|
#define SPI2_MISO_PIN PB14
|
||||||
#define SPI2_MOSI_PIN PB15
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
#define SPI3_NSS_PIN PA15
|
#define SPI3_NSS_PIN PA15
|
||||||
#define SPI3_SCK_PIN PC10
|
#define SPI3_SCK_PIN PC10
|
||||||
#define SPI3_MISO_PIN PC11
|
#define SPI3_MISO_PIN PC11
|
||||||
#define SPI3_MOSI_PIN PC12
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
@ -142,17 +140,16 @@
|
||||||
#define CURRENT_METER_SCALE_DEFAULT 250 // 3.3/120A = 25mv/A
|
#define CURRENT_METER_SCALE_DEFAULT 250 // 3.3/120A = 25mv/A
|
||||||
|
|
||||||
#define BINDPLUG_PIN PB2
|
#define BINDPLUG_PIN PB2
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART6
|
#define SERIALRX_UART SERIAL_PORT_UART5
|
||||||
#define TELEMETRY_UART SERIAL_PORT_USART1
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
#define TARGET_IO_PORTD (BIT(2))
|
#define TARGET_IO_PORTD (BIT(2))
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 9
|
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(10) )
|
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
||||||
|
|
||||||
|
|
|
@ -1,12 +1,10 @@
|
||||||
F7X2RE_TARGETS += $(TARGET)
|
F7X2RE_TARGETS += $(TARGET)
|
||||||
FEATURES += SDCARD VCP
|
FEATURES += VCP ONBOARDFLASH SDCARD
|
||||||
TARGET_SRC = \
|
TARGET_SRC = \
|
||||||
drivers/accgyro/accgyro_mpu.c \
|
drivers/accgyro/accgyro_mpu.c \
|
||||||
drivers/accgyro/accgyro_spi_icm20689.c\
|
|
||||||
drivers/accgyro/accgyro_mpu6500.c \
|
drivers/accgyro/accgyro_mpu6500.c \
|
||||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
drivers/light_ws2811strip_hal.c \
|
drivers/light_ws2811strip_hal.c \
|
||||||
drivers/max7456.c
|
drivers/max7456.c
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue