From cf2b89c4f1a0cce6dad25dcbd2200ff3f7be7aa7 Mon Sep 17 00:00:00 2001 From: Huibean Date: Sat, 27 Jun 2020 19:51:52 +0800 Subject: [PATCH] AP_HAL_ChibiOS:add mazzy star drone hwdef --- .../hwdef/MazzyStarDrone/README.md | 5 + .../hwdef/MazzyStarDrone/hwdef-bl.dat | 47 +++++ .../hwdef/MazzyStarDrone/hwdef.dat | 179 ++++++++++++++++++ 3 files changed, 231 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/README.md new file mode 100644 index 0000000000..499b5bbe8e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/README.md @@ -0,0 +1,5 @@ +# Mazzy Star Drone + +https://www.vimdrones.com + +The Mazzy Star Drone is a ready to fly drone for making drone light show produced by [Vimdrones](https://www.vimdrones.com) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef-bl.dat new file mode 100644 index 0000000000..553cc30fea --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef-bl.dat @@ -0,0 +1,47 @@ +# hw definition file for processing by chibios_pins.py +# for Mazzy Star Drone bootloader + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID 188 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +define STM32_LSECLK 32768U +define STM32_LSEDRV (3U << 3U) + +define STM32_PLLSRC STM32_PLLSRC_HSE +define STM32_PLLM_VALUE 8 +define STM32_PLLN_VALUE 432 +define STM32_PLLP_VALUE 2 +define STM32_PLLQ_VALUE 9 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 96 + +# board voltage +STM32_VDD 330U + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PA2 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef.dat new file mode 100644 index 0000000000..d10819294e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MazzyStarDrone/hwdef.dat @@ -0,0 +1,179 @@ +# for Mazzy Star Drone FC. + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID 188 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +define STM32_LSECLK 32768U +define STM32_LSEDRV (3U << 3U) + +define STM32_PLLSRC STM32_PLLSRC_HSE +define STM32_PLLM_VALUE 8 +define STM32_PLLN_VALUE 432 +define STM32_PLLP_VALUE 2 +define STM32_PLLQ_VALUE 9 + +FLASH_SIZE_KB 1024 + +# leave 2 sectors free +FLASH_RESERVE_START_KB 96 + +# board voltage +STM32_VDD 330U + +# only one I2C bus +I2C_ORDER I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 UART4 USART3 + +# buzzer +PD15 TIM4_CH4 TIM4 GPIO(77) ALARM +#PD15 BUZZER OUTPUT GPIO(80) LOW +#define HAL_BUZZER_PIN 80 +#define HAL_BUZZER_ON 1 +#define HAL_BUZZER_OFF 0 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for SDCard +PA4 SDCARD_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# for ICM20689 +PE4 ICM20689_CS CS + +# for BMI055 +PB4 BMI055_G_CS CS +PD3 BMI055_A_CS CS + +# GPIOs +PD12 HEATER_EN OUTPUT LOW GPIO(59) +define HAL_HEATER_GPIO_PIN 59 + +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 60 + +# SPI temperature sensor +PD0 TSENSE_CS CS + +# drdy pins +PE1 DRDY1_ICM20689 INPUT +PB3 DRDY2_BMI055_GYRO INPUT +PD2 DRDY3_BMI055_ACC INPUT +PB5 DRDY5_BMI055_GYRO INPUT +PD1 DRDY6_BMI055_ACC INPUT + +# I2C1 for baro +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 10.1 +define HAL_BATT_CURR_SCALE 17.0 + +PC5 RSSI_ADC ADC1 + +PA2 LED0 OUTPUT LOW + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 (GPS) +PB11 USART3_RX USART3 +PB10 USART3_TX USART3 + +# UART4 (GPS2) +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +# USART6, RX only for RCIN +PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW +PC6 USART6_TX USART6 NODMA LOW + +# UART7 USED BY ESC FROM ORIGINAL DESIGN +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# Motors +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(34) +PB1 TIM1_CH3N TIM1 PWM(2) GPIO(35) +PE9 TIM1_CH1 TIM1 PWM(3) GPIO(39) +PE11 TIM1_CH2 TIM1 PWM(4) GPIO(41) +PC9 TIM3_CH4 TIM3 PWM(5) GPIO(66) +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(25) + +# extra PWM outs +#PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) # led pin +#PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57) # buzzer pin (need to comment out buzzer) + +DMA_PRIORITY S* + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +# spi devices +SPIDEV icm20689 SPI4 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV bmi055_g SPI4 DEVID2 BMI055_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi055_a SPI4 DEVID3 BMI055_A_CS MODE3 10*MHZ 10*MHZ + +SPIDEV sdcard SPI1 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +define HAL_SPI_CHECK_CLOCK_FREQ 1 + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +# define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +# define HAL_PROBE_EXTERNAL_I2C_COMPASSES +# define HAL_COMPASS_DEFAULT HAL_COMPASS_IST8310_I2C +# define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90 + +# two IMU +IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_270 +IMU Invensense SPI:icm20689 ROTATION_YAW_180 + +# one BARO +BARO BMP280 I2C:0:0x76 + +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +define BOARD_PWM_COUNT_DEFAULT 6 +define STM32_PWM_USE_ADVANCED TRUE + +# we are low on flash on this board +define HAL_MINIMIZE_FEATURES 1