mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Use unified clock specs, remove per target specs.
This commit is contained in:
parent
ec8d363adb
commit
d4cfff2e9d
52 changed files with 17 additions and 305 deletions
|
@ -55,7 +55,7 @@ uint8_t icm20689SpiDetect(const busDevice_t *bus)
|
|||
{
|
||||
icm20689SpiInit(bus);
|
||||
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed
|
||||
|
||||
spiBusWriteRegister(bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET);
|
||||
|
||||
|
@ -119,7 +119,7 @@ void icm20689GyroInit(gyroDev_t *gyro)
|
|||
{
|
||||
mpuGyroInit(gyro);
|
||||
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
|
||||
|
||||
spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET);
|
||||
delay(100);
|
||||
|
|
|
@ -105,7 +105,7 @@ void mpu6000SpiGyroInit(gyroDev_t *gyro)
|
|||
|
||||
mpu6000AccAndGyroInit(gyro);
|
||||
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
|
||||
|
||||
// Accel and Gyro DLPF Setting
|
||||
spiBusWriteRegister(&gyro->bus, MPU6000_CONFIG, mpuGyroDLPF(gyro));
|
||||
|
@ -128,7 +128,7 @@ void mpu6000SpiAccInit(accDev_t *acc)
|
|||
uint8_t mpu6000SpiDetect(const busDevice_t *bus)
|
||||
{
|
||||
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
|
||||
|
||||
spiBusWriteRegister(bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||
|
||||
|
@ -175,7 +175,7 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro)
|
|||
return;
|
||||
}
|
||||
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON);
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION);
|
||||
|
||||
// Device Reset
|
||||
spiBusWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
|
||||
|
|
|
@ -124,7 +124,7 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
|
|||
return;
|
||||
}
|
||||
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers
|
||||
spiSetDivisor(gyro->bus.busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed for writing to slow registers
|
||||
|
||||
mpu9250SpiWriteRegister(&gyro->bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
delay(50);
|
||||
|
@ -152,7 +152,7 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) {
|
|||
uint8_t mpu9250SpiDetect(const busDevice_t *bus)
|
||||
{
|
||||
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATON); //low speed
|
||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed
|
||||
mpu9250SpiWriteRegister(bus, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
||||
|
||||
uint8_t attemptsRemaining = 20;
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
Flash M25p16 tolerates 20mhz, SPI_CLOCK_FAST should sit around 20 or less.
|
||||
*/
|
||||
typedef enum {
|
||||
SPI_CLOCK_INITIALIZATON = 256,
|
||||
SPI_CLOCK_INITIALIZATION = 256,
|
||||
#if defined(STM32F4)
|
||||
SPI_CLOCK_SLOW = 128, //00.65625 MHz
|
||||
SPI_CLOCK_STANDARD = 8, //10.50000 MHz
|
||||
|
|
|
@ -50,6 +50,12 @@
|
|||
#define SDCARD_TIMEOUT_INIT_MILLIS 200
|
||||
#define SDCARD_MAX_CONSECUTIVE_FAILURES 8
|
||||
|
||||
/* SPI_CLOCK_INITIALIZATION (256) is the slowest (Spec calls for under 400KHz) */
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER SPI_CLOCK_INITIALIZATION
|
||||
|
||||
/* Operational speed <= 25MHz */
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER SPI_CLOCK_FAST
|
||||
|
||||
/* Break up 512-byte SD card sectors into chunks of this size when writing without DMA to reduce the peak overhead
|
||||
* per call to sdcard_poll().
|
||||
*/
|
||||
|
|
|
@ -68,18 +68,10 @@
|
|||
#define USE_BARO_BMP280
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PB11
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB10
|
||||
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -82,18 +82,10 @@
|
|||
#define BMP280_SPI_INSTANCE SPI3
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PB11
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB10
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -137,14 +137,8 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PD3
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
|
||||
|
|
|
@ -62,17 +62,10 @@
|
|||
#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_PIN PC3
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -120,16 +120,10 @@
|
|||
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
|
|
|
@ -75,18 +75,10 @@
|
|||
#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
|
||||
// SPI2 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_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -46,16 +46,10 @@
|
|||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -73,10 +73,6 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -68,9 +68,6 @@
|
|||
#define SDCARD_DETECT_PIN PA8
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -61,20 +61,11 @@
|
|||
#define USE_BARO_MS5611
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PE15
|
||||
|
||||
// SPI2 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_Stream3
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_USB_DETECT
|
||||
#define USB_DETECT_PIN PA9
|
||||
|
|
|
@ -106,18 +106,10 @@
|
|||
|
||||
// *************** SDCARD *****************************
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PB9
|
||||
|
||||
// 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_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -127,15 +127,11 @@
|
|||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PB5
|
||||
#define SDCARD_SPI_INSTANCE SPI1
|
||||
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4
|
||||
|
||||
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_NONE
|
||||
|
||||
|
|
|
@ -67,9 +67,6 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -116,18 +116,11 @@
|
|||
#else
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PB2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -76,24 +76,14 @@
|
|||
#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
|
||||
// SPI2 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_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#endif
|
||||
|
|
|
@ -80,14 +80,8 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 13.5MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
|
||||
|
|
|
@ -125,14 +125,8 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PD8
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI1
|
||||
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 3
|
||||
|
||||
|
|
|
@ -81,21 +81,11 @@
|
|||
|
||||
#if defined(KIWIF4V2)
|
||||
#define USE_SDCARD
|
||||
|
||||
|
||||
//#define SDCARD_DETECT_PIN PB9
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
|
||||
// SPI2 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_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -70,9 +70,6 @@
|
|||
#define SDCARD_DETECT_PIN PC13
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -77,18 +77,11 @@
|
|||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC13
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#endif
|
||||
|
|
|
@ -105,15 +105,8 @@
|
|||
// *************** SD Card **************************
|
||||
#define USE_SDCARD
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#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 0
|
||||
|
||||
|
|
|
@ -96,11 +96,6 @@
|
|||
#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_STREAM_TX_FULL DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -86,12 +86,6 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// // Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
#define USE_ADC
|
||||
|
|
|
@ -122,11 +122,6 @@
|
|||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
#define SDCARD_SPI_CS_CFG IOCFG_OUT_OD
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -54,17 +54,10 @@
|
|||
#define GYRO_1_ALIGN CW0_DEG
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
|
||||
// SPI2 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_STREAM_TX_FULL DMA1_Stream5
|
||||
//#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -73,17 +73,10 @@
|
|||
#define USE_CMS
|
||||
|
||||
//#define USE_SDCARD
|
||||
//
|
||||
//#define SDCARD_SPI_INSTANCE SPI2
|
||||
//#define SDCARD_SPI_CS_PIN PB12
|
||||
//// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
//#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
//// Divide to under 25MHz for normal operation:
|
||||
//#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
//
|
||||
//// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
//#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
|
|
|
@ -126,14 +126,8 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PF14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
|
||||
|
|
|
@ -126,21 +126,14 @@
|
|||
#define SPI4_MOSI_PIN PE14
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
//#define SDCARD_DETECT_INVERTED
|
||||
//#define SDCARD_DETECT_PIN PF14
|
||||
|
||||
//#define SDCARD_SPI_INSTANCE SPI4
|
||||
//#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
|
||||
//#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
//#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
//#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
//#define SDCARD_DMA_CHANNEL 4
|
||||
|
||||
#define USE_SDCARD_SDIO
|
||||
|
||||
#define SDIO_DMA DMA2_Stream3
|
||||
#define SDCARD_SPI_CS_PIN NONE //This is not used on SDIO, has to be kept for now to keep compiler happy
|
||||
|
||||
|
|
|
@ -142,19 +142,12 @@
|
|||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative
|
||||
|
||||
#ifndef USE_DSHOT
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
#endif
|
||||
|
|
|
@ -156,11 +156,6 @@
|
|||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -186,14 +186,8 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PE3
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI4
|
||||
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream1
|
||||
#define SDCARD_DMA_CHANNEL 4
|
||||
|
||||
|
|
|
@ -163,12 +163,6 @@
|
|||
#define SDCARD_DETECT_PIN PC0
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN SPI3_NSS_PIN
|
||||
|
||||
// SPI2 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_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -69,19 +69,11 @@
|
|||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI1
|
||||
#define SDCARD_SPI_CS_GPIO GPIOB
|
||||
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel3
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
|
|
|
@ -143,16 +143,10 @@
|
|||
#define RTC6705_CS_PIN PC14
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -157,18 +157,11 @@
|
|||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -179,18 +179,11 @@
|
|||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -140,18 +140,11 @@
|
|||
#define SPI_SHARED_MAX7456_AND_RTC6705
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
|
||||
// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
|
|
|
@ -148,17 +148,10 @@
|
|||
#endif
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -161,18 +161,10 @@
|
|||
//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#define SDCARD_DETECT_PIN PC14
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
// 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -149,15 +149,8 @@
|
|||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PC3
|
||||
|
||||
// SPI3 is on the APB1 bus whose clock runs at 54MHz. Divide to under 400kHz for init:
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 54Mhz/256 = 210kHz
|
||||
// Divide to under 25MHz for normal operation:
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 54Mhz/3 = 18Mhz // FIXME currently running slower than 18mhz for testing.
|
||||
|
||||
#define SDCARD_DMA_STREAM_TX_FULL DMA1_Stream7
|
||||
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_0
|
||||
|
||||
|
|
|
@ -158,17 +158,10 @@
|
|||
//#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
//#define USE_SDCARD
|
||||
//
|
||||
//#define SDCARD_SPI_INSTANCE SPI2
|
||||
//#define SDCARD_SPI_CS_PIN PB12
|
||||
//// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
|
||||
//#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
|
||||
//// Divide to under 25MHz for normal operation:
|
||||
//#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||
//
|
||||
//// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
|
||||
//#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
|
||||
|
||||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
|
|
|
@ -97,11 +97,6 @@
|
|||
#define USE_SDCARD
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PD8
|
||||
// SPI2 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 // 5,5MHz
|
||||
|
||||
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
|
@ -70,9 +70,6 @@
|
|||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
|
||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define USE_I2C_DEVICE_2
|
||||
|
|
|
@ -67,11 +67,6 @@
|
|||
#define SDCARD_DETECT_PIN PE2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
||||
#endif
|
||||
|
|
|
@ -55,9 +55,7 @@
|
|||
#define MS5611_I2C_INSTANCE I2CDEV_1
|
||||
|
||||
#define USE_SDCARD
|
||||
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI2
|
||||
#define SDCARD_SPI_CS_PIN PB12
|
||||
|
@ -65,20 +63,14 @@
|
|||
|
||||
/*
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PB3
|
||||
*/
|
||||
|
||||
// SPI2 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_Stream4
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
|
|
@ -125,6 +125,7 @@
|
|||
//SD CARD
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SDIO
|
||||
|
||||
#define SDIO_DMA DMA2_Stream3
|
||||
#define SDCARD_SPI_CS_PIN NONE //This is not used on SDIO, has to be kept for now to keep compiler happy
|
||||
#define SDCARD_DETECT_PIN PB15
|
||||
|
|
|
@ -85,16 +85,9 @@
|
|||
// SD Card
|
||||
#define USE_SDCARD
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
|
||||
#define SDCARD_DETECT_PIN PD2
|
||||
#define SDCARD_SPI_INSTANCE SPI3
|
||||
#define SDCARD_SPI_CS_PIN PA15
|
||||
|
||||
// SPI2 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_Stream5
|
||||
#define SDCARD_DMA_CHANNEL 0
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue