diff --git a/src/config/ATSTARTF435/config.h b/src/config/ATSTARTF435/config.h new file mode 100644 index 0000000000..f44728f06c --- /dev/null +++ b/src/config/ATSTARTF435/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +#define FC_TARGET_MCU AT32F435 + +#define BOARD_NAME ATSTARTF435 +#define MANUFACTURER_ID AT + +// AT-START-F435 V1.0 LED assignments to use as a default +#define LED0_PIN PD13 // Labelled LED2 Red +#define LED1_PIN PD14 // Labelled LED3 Amber +#define LED2_PIN PD15 // Labelled LED4 Green + +// AT-START-F435 J7 connector SPI 2 +#define SPI2_SCK_PIN PD1 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PD4 + +#define J7_NSS PD0 + +#define GYRO_1_CS_PIN J7_NSS +#define GYRO_1_SPI_INSTANCE SPI2 + +#define USE_EXTI +#define USE_GYRO_EXTI +#define GYRO_1_EXTI_PIN PB11 + +#define USE_ACCGYRO_BMI160 + diff --git a/src/config/REVO_AT/config.h b/src/config/REVO_AT/config.h new file mode 100644 index 0000000000..a35e864f0b --- /dev/null +++ b/src/config/REVO_AT/config.h @@ -0,0 +1,50 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +#define FC_TARGET_MCU AT32F435 + +// REVO with STM32F405 swapped for an AT32F435 + +#define BOARD_NAME REVO_AT +#define MANUFACTURER_ID OPEN + +#define LED0_PIN PB5 + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define GYRO_1_ALIGN CW270_DEG + +// MPU6000 interrupts +#define USE_EXTI +#define USE_GYRO_EXTI +#define GYRO_1_EXTI_PIN PC4 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_FLASH_M25P16 diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index 496e9d51a0..dc512d3ae0 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -50,6 +50,10 @@ uint8_t eepromData[EEPROM_SIZE]; # define FLASH_PAGE_SIZE ((uint32_t)0x4000) # elif defined(STM32F446xx) # define FLASH_PAGE_SIZE ((uint32_t)0x4000) +# elif defined(AT32F435ZMT7) || defined(AT32F435RMT7) +# define FLASH_PAGE_SIZE ((uint32_t)0x1000) // 4K sectors +# elif defined(AT32F435RGT7) +# define FLASH_PAGE_SIZE ((uint32_t)0x0800) // 2K sectors // F7 #elif defined(STM32F722xx) # define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors diff --git a/src/main/drivers/at32/bus_spi_at32bsp.c b/src/main/drivers/at32/bus_spi_at32bsp.c index 027d75b3cc..fd92be0ea8 100644 --- a/src/main/drivers/at32/bus_spi_at32bsp.c +++ b/src/main/drivers/at32/bus_spi_at32bsp.c @@ -44,7 +44,7 @@ static spi_init_type defaultInit = { .first_bit_transmission = SPI_FIRST_BIT_MSB, .mclk_freq_division = SPI_MCLK_DIV_8, .clock_polarity = SPI_CLOCK_POLARITY_HIGH, - .clock_phase = SPI_CLOCK_PHASE_2EDGE + .clock_phase = SPI_CLOCK_PHASE_2EDGE }; static uint16_t spiDivisorToBRbits(spi_type *instance, uint16_t divisor) diff --git a/src/main/drivers/at32/debug.c b/src/main/drivers/at32/debug.c index df1cc96180..038ed5a196 100644 --- a/src/main/drivers/at32/debug.c +++ b/src/main/drivers/at32/debug.c @@ -23,7 +23,6 @@ #include "build/debug.h" #include "drivers/io.h" -#ifdef DEBUG // DEBUG=GDB on command line void debugInit(void) { IO_t io = IOGetByTag(DEFIO_TAG_E(PA13)); // SWDIO @@ -35,4 +34,3 @@ void debugInit(void) IOInit(io, OWNER_SWD, 0); } } -#endif diff --git a/src/main/drivers/at32/platform_at32.h b/src/main/drivers/at32/platform_at32.h index eb51ed31c3..63bd9cf7b3 100644 --- a/src/main/drivers/at32/platform_at32.h +++ b/src/main/drivers/at32/platform_at32.h @@ -1,3 +1,24 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute + * this software and/or modify this software 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. + * + * Betaflight is distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once #if defined(AT32F435ZMT7) @@ -70,7 +91,6 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define USE_LATE_TASK_STATISTICS -/* #ifndef SPI1_SCK_PIN #define SPI1_SCK_PIN PA5 #define SPI1_MISO_PIN PA6 @@ -106,4 +126,3 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define SPI6_MISO_PIN NONE #define SPI6_MOSI_PIN NONE #endif -*/ diff --git a/src/main/drivers/stm32/debug.c b/src/main/drivers/stm32/debug.c index df1cc96180..038ed5a196 100644 --- a/src/main/drivers/stm32/debug.c +++ b/src/main/drivers/stm32/debug.c @@ -23,7 +23,6 @@ #include "build/debug.h" #include "drivers/io.h" -#ifdef DEBUG // DEBUG=GDB on command line void debugInit(void) { IO_t io = IOGetByTag(DEFIO_TAG_E(PA13)); // SWDIO @@ -35,4 +34,3 @@ void debugInit(void) IOInit(io, OWNER_SWD, 0); } } -#endif diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 95bf8cfdaf..5aa410f215 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -1014,9 +1014,7 @@ void init(void) spiInitBusDMA(); #endif -#ifdef DEBUG debugInit(); -#endif unusedPinsInit(); diff --git a/src/main/target/AT32F435/target.h b/src/main/target/AT32F435/target.h index 4239620b25..80a1603596 100644 --- a/src/main/target/AT32F435/target.h +++ b/src/main/target/AT32F435/target.h @@ -30,56 +30,31 @@ #define AT32F435 #endif -// AT-START-F435 V1.0 LED assignments to use as a default -#define LED0_PIN PD13 // Labelled LED2 Red -#define LED1_PIN PD14 // Labelled LED3 Amber -#define LED2_PIN PD15 // Labelled LED4 Green - -//#define USE_I2C_DEVICE_1 - #define USE_UART1 -// AT-START-F435 V1.0 UART 1 assignments to use as a default -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 -#define USE_MSP_UART SERIAL_PORT_USART1 - #define USE_UART2 #define USE_UART3 #define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 3) -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff - -//#define USE_I2C -//#define I2C_FULL_RECONFIGURABILITY +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff #define USE_SPI +#define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 #define USE_SPI_DMA_ENABLE_LATE -// AT-START-F435 J7 connector SPI 1 -#define SPI2_SCK_PIN PD1 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PD4 - -#define J7_NSS PD0 - -#define GYRO_1_CS_PIN J7_NSS -#define GYRO_1_SPI_INSTANCE SPI2 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 #define USE_EXTI #define USE_GYRO_EXTI -#define GYRO_1_EXTI_PIN PB11 -#define USE_ACCGYRO_BMI160 #define USE_USB_DETECT #define USE_VCP -//#define USE_SOFTSERIAL1 -//#define USE_SOFTSERIAL2 - #define UNIFIED_SERIAL_PORT_COUNT 1 @@ -88,6 +63,7 @@ #define USE_CUSTOM_DEFAULTS #define USE_PWM_OUTPUT +// Remove these undefines as support is added #undef USE_BEEPER #undef USE_LED_STRIP #undef USE_TRANSPONDER @@ -111,13 +87,3 @@ #undef USE_FLASH #undef USE_FLASHFS #undef USE_FLASH_CHIP - -#if defined(AT32F435ZMT7) || defined(AT32F435RMT7) -// 4k sectors -#define FLASH_PAGE_SIZE ((uint32_t)0x1000) -#elif defined(AT32F435RGT7) -// 2K page sectors -#define FLASH_PAGE_SIZE ((uint32_t)0x0800) -#endif - -#define USE_EXTI diff --git a/src/main/target/SITL/sitl.c b/src/main/target/SITL/sitl.c index b4de5b2408..f42b769400 100644 --- a/src/main/target/SITL/sitl.c +++ b/src/main/target/SITL/sitl.c @@ -737,6 +737,11 @@ void spektrumBind(rxConfig_t *rxConfig) printf("spektrumBind\n"); } +void debugInit(void) +{ + printf("debugInit\n"); +} + void unusedPinsInit(void) { printf("unusedPinsInit\n");