diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg new file mode 100644 index 0000000000..d29fe9d108 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_BottomView.jpeg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg new file mode 100644 index 0000000000..7f53e471f7 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/MFT-SEMA100_TopView.jpeg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md new file mode 100644 index 0000000000..0c8b397380 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/README.md @@ -0,0 +1,111 @@ +# MFT-SEMA100 Flight Controller + +The MFT-SEMA100 is a flight controller designed and produced by MFT Savunma ve Havacılık LTD. ŞTİ. + +## Features + + - STM32H743 microcontroller + - BMI088 IMU + - BMP390 barometer + - LIB3MDL magnetometer + - MicroSD Card Slot + - 5 UARTs + - 12 PWM outputs + - 2 CANs + - 2 I2Cs + +## Physical + +![MFT-SEMA100_Top_View](MFT-SEMA100_TopView.jpeg) + +![MFT-SEMA100_Bottom_View](MFT-SEMA100_BottomView.jpeg) + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART2 (MAVLink2, DMA-enabled) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART5 (GPS2, DMA-enabled) + - SERIAL5 -> UART7 (DMA-enabled) + - SERIAL6 -> UART8 (RX only) + +## Connectors + +All pins are 2.54 mm Pin Headers + +## Power Connector + +XT30-PW 5V Input for powering the board + +## RC Input + +The default RC input is configured on the UART8 RCIN pin. + + +## PWM Output + +The MFT-SEMA100 supports up to 12 PWM outputs. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2 are Group 1; + +3, 4 are Group 2; + +5, 6, 7, 8 are Group 3; + +9, 10 are Group 4; + +11, 12 are Group 5; + +Channels within the same group need to use the same output rate. + +## GPIOs +The numbering of the GPIOs for PIN variables in ArduPilot is: + +PWM1 50 +PWM2 51 +PWM3 52 +PWM4 53 +PWM5 54 +PWM6 55 +PWM7 56 +PWM8 57 + +PWM9 58 +PWM10 59 +PWM11 60 +PWM12 61 + + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 19 + - BATT_CURR_PIN 8 + - BATT_VOLT_MULT 10 + - BATT_CURR_SCALE 10 + +## Compass + +The MFT-SEMA100 has a built-in compass sensor (LIB3MDL), and you can also attach an external compass using I2C on the SDA and SCL connector. + +## IMU Heater + +The IMU heater in the MFT-SEMA100 can be controlled with the BRD_HEAT_TARG parameter, which is in degrees C. + +## Mechanical + + - Mounting: 55 x 56 mm, Φ4 mm + - Dimensions: 64 x 65 x 10 mm + - Weight: 15g + +## Loading Firmware + +The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm new file mode 100644 index 0000000000..8fbf2c05bc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/defaults.parm @@ -0,0 +1,4 @@ +# setup the temperature compensation +BRD_HEAT_TARG 45 +BRD_HEAT_P 50 +BRD_HEAT_I 0.07 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat new file mode 100644 index 0000000000..3d0ffb248a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef-bl.dat @@ -0,0 +1,51 @@ +# hw definition file for processing by chibios_hwdef.py +# for MFT-SEMA100 board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 2000 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + + + +PC13 LED_BOOTLOADER OUTPUT HIGH GPIO(0) +PC6 LED_ACTIVITY OUTPUT HIGH GPIO(1) # optional + + +define HAL_LED_ON 1 + + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PC4 SDCARD_DETECT INPUT + +# Add CS pins to ensure they are high in bootloader +PE3 BMI088_A_CS CS +PE4 BMI088_G_CS CS +PA15 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat new file mode 100644 index 0000000000..01406f2bf2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MFT-SEMA100/hwdef.dat @@ -0,0 +1,217 @@ +# hw definition file for processing by chibios_hwdef.py for MFT-SEMA100 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 2000 + +FLASH_SIZE_KB 2048 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +USB__STRING_MANUFACTURER "MFT" +USB_STRING_PRODUCT "MFT-SEMA100" + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART5 UART7 UART8 OTG2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS +PH15 USB_HS_ENABLE OUTPUT HIGH +define USB_HW_ENABLE_HS 0 + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - SD CARD +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PA15 SDCARD_CS CS +PC4 SDCARD_DETECT INPUT + +# SPI2 - External +PD3 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + + +# SPI4 - GYRO +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensor +PE3 BMI088_A_CS CS +PE4 BMI088_G_CS CS + + +# I2C buses + + +#I2C1 is External +PB8 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 for onboard mag +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# I2C3 for onboard BAROMETER +PA8 I2C3_SCL I2C3 +PC9 I2C3_SDA I2C3 + +# I2C4 is External +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C2 I2C3 I2C4 I2C1 + + +define HAL_I2C_INTERNAL_MASK 1 + +# drdy pins +PE11 DRDY1_LIS3MDL INPUT + + +# UARTs +#USART1 TX RX 1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USART2 is TX RX 2 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 + +# USART3 is TX RX 3 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# UART5 is TX RX 4 +PD2 UART5_RX UART5 NODMA +PC12 UART5_TX UART5 NODMA + +# UART7 is TX RX 5 +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PE9 UART7_RTS UART7 + + +# SBUS, DSM port +PE0 UART8_RX UART8 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN + + + +# PWM AUX channels +PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50) +PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51) +PC7 TIM8_CH2 TIM8 PWM(3) GPIO(52) +PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) +PA0 TIM5_CH1 TIM5 PWM(5) GPIO(54) +PA1 TIM5_CH2 TIM5 PWM(6) GPIO(55) +PA2 TIM5_CH3 TIM5 PWM(7) GPIO(56) +PA3 TIM5_CH4 TIM5 PWM(8) GPIO(57) + +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) +PA6 TIM3_CH1 TIM3 PWM(11) GPIO(60) +PA7 TIM3_CH2 TIM3 PWM(12) GPIO(61) + + +# allow for 14 PWMs by default + +# PWM output for buzzer +PB15 TIM12_CH2 TIM12 GPIO(77) ALARM + + +# analog in +PA5 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC5 BATT_CURRENT_SENS ADC1 SCALE(1) + + +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 19 +define HAL_BATT_VOLT_SCALE 10 + +#define HAL_BATT2_VOLT_PIN 15 +#define HAL_BATT2_VOLT_SCALE 9 + +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_CURR_SCALE 10 + + + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# 2nd CAN bus +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +# control for silent (no output) for CAN +PD4 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +PD11 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# GPIOs + +PD10 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + + +#BARO +BARO BMP388 I2C:1:0x77 + +# SPI devices +SPIDEV bmi088_a SPI4 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI4 DEVID2 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV sdcard SPI1 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ + + +# IMU +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS LIS3MDL I2C:ALL_INTERNAL:0x1C false ROTATION_NONE + + +#LEDs +PC13 LED_BOOTLOADER OUTPUT HIGH GPIO(0) +PC6 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 + +#STORAGE +STORAGE_FLASH_PAGE 14 +define HAL_STORAGE_SIZE 32768 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +DMA_PRIORITY ADC* SPI4* TIM*UP* +DMA_NOSHARE SPI4* TIM*UP* + +define DEFAULT_NTF_LED_TYPES 743