diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk new file mode 100644 index 0000000000..2f6492da96 --- /dev/null +++ b/src/main/target/OMNIBUSF4/OMNIBUSF4SD.mk @@ -0,0 +1,2 @@ +# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping +FEATURES = VCP SDCARD diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index eaaba9beec..38fba42c97 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -24,8 +24,13 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port) - { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3 +#ifdef OMNIBUSF4SD + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM4, NULL, 0, 0}, // PPM + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM4, NULL, 0, 0}, // S2_IN +#else + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN +#endif { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 2ec1fc1c56..d69709ae8f 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -1,23 +1,25 @@ /* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify + * This 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, + * This software 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 . + * along with this software. If not, see . */ #pragma once +#ifdef OMNIBUSF4SD +#define TARGET_BOARD_IDENTIFIER "OBSD" +#else #define TARGET_BOARD_IDENTIFIER "OBF4" +#endif #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) @@ -26,6 +28,7 @@ #define USBD_SERIALNUMBER_STRING "0x8020000" #endif + #define LED0 PB5 //#define LED1 PB4 @@ -60,25 +63,46 @@ #define BARO #define USE_BARO_MS5611 +#ifdef OMNIBUSF4SD + #define USE_BARO_BMP280 + #define USE_BARO_SPI_BMP280 + #define BMP280_SPI_INSTANCE SPI3 + #define BMP280_CS_PIN PB3 // v1 +#endif #define OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2) +#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) -//#define MAX7456_DMA_CHANNEL_TX DMA1_Stream5 -//#define MAX7456_DMA_CHANNEL_RX DMA1_Stream0 -//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_ST0_HANDLER +#ifdef OMNIBUSF4SD + #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + #define USE_SDCARD + #define USE_SDCARD_SPI2 -//#define PITOT -//#define USE_PITOT_MS4525 -//#define MS4525_BUS I2C_DEVICE_EXT + #define SDCARD_DETECT_INVERTED + #define SDCARD_DETECT_PIN PB7 + #define SDCARD_SPI_INSTANCE SPI2 + #define SDCARD_SPI_CS_PIN SPI2_NSS_PIN -#define M25P16_CS_PIN SPI3_NSS_PIN -#define M25P16_SPI_INSTANCE SPI3 + // 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 USE_FLASHFS -#define USE_FLASH_M25P16 + #define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 + #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4 + #define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 + #define SDCARD_DMA_CHANNEL DMA_Channel_0 +#else + #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + #define M25P16_CS_PIN SPI3_NSS_PIN + #define M25P16_SPI_INSTANCE SPI3 + #define USE_FLASHFS + #define USE_FLASH_M25P16 +#endif #define USE_VCP #define VBUS_SENSING_PIN PC5 @@ -110,14 +134,26 @@ #define USE_SPI_DEVICE_1 +#ifdef OMNIBUSF4SD + #define USE_SPI_DEVICE_2 + #define SPI2_NSS_PIN PB12 + #define SPI2_SCK_PIN PB13 + #define SPI2_MISO_PIN PB14 + #define SPI2_MOSI_PIN PB15 +#endif + #define USE_SPI_DEVICE_3 -#define SPI3_NSS_PIN PB3 +#ifdef OMNIBUSF4SD + #define SPI3_NSS_PIN PA15 +#else + #define SPI3_NSS_PIN PB3 +#endif #define SPI3_SCK_PIN PC10 #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define USE_I2C -#define I2C_DEVICE (I2CDEV_1) +//#define USE_I2C +//#define I2C_DEVICE (I2CDEV_1) #define USE_ADC #define CURRENT_METER_ADC_PIN PC1 @@ -131,8 +167,8 @@ #define SENSORS_SET (SENSOR_ACC) -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_VBAT) #define AVOID_UART1_FOR_PWM_PPM @@ -144,4 +180,4 @@ #define TARGET_IO_PORTD 0xffff #define USABLE_TIMER_CHANNEL_COUNT 12 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/OMNIBUSF4/target.mk b/src/main/target/OMNIBUSF4/target.mk index af8a1adbfc..37ad7af0c6 100644 --- a/src/main/target/OMNIBUSF4/target.mk +++ b/src/main/target/OMNIBUSF4/target.mk @@ -4,6 +4,8 @@ FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro_spi_mpu6000.c \ drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_spi_bmp280.c \ drivers/compass_hmc5883l.c \ drivers/max7456.c \ io/vtx_smartaudio.c