mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_HAL_ChibiOS: add hwdef MicoAir743v2
Update README.md: add bluetooth introduction to features Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> Update README.md: fix description about SERIAL8 Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> Update README.md: fix description about RC Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> Update README.md: add description about "LED" pin Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> Update README.md: fix description about Loading Firmware Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> Update README.md: fix description about update firmware Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> remove defaults.parm and defined default params in hwdef file Update README.md: fix description about osd Co-authored-by: Henry Wurzburg <hwurzburg@yahoo.com> remove parameter define about serial4 Update README.md: add a section about BlueTooth
This commit is contained in:
parent
e0068ec81c
commit
9e035518c7
Binary file not shown.
After Width: | Height: | Size: 394 KiB |
Binary file not shown.
After Width: | Height: | Size: 807 KiB |
118
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/README.md
Normal file
118
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/README.md
Normal file
@ -0,0 +1,118 @@
|
||||
# MicoAir743v2 Flight Controller
|
||||
|
||||
The MicoAir743v2 is a flight controller designed and produced by [MicoAir Tech](http://micoair.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32H743 microcontroller
|
||||
- BMI088/BMI270 dual IMUs
|
||||
- Integrated BlueTooth module for telemetry
|
||||
- SPL06 barometer
|
||||
- QMC5883L magnetometer
|
||||
- AT7456E OSD
|
||||
- 9V 3A BEC; 5V 3A BEC
|
||||
- MicroSD Card Slot
|
||||
- 8 UARTs
|
||||
- 11 PWM outputs
|
||||
- 1 I2C
|
||||
- 1 SWD
|
||||
|
||||
## Physical
|
||||
|
||||
![MicoAir H743 v2.0 Physical Size](MicoAir743v2_Physical_Size.jpg)
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (MAVLink2, DMA-enabled)
|
||||
- SERIAL2 -> UART2 (DisplayPort, DMA-enabled)
|
||||
- SERIAL3 -> UART3 (GPS, DMA-enabled)
|
||||
- SERIAL4 -> UART4 (MAVLink2, DMA-enabled)
|
||||
- SERIAL5 -> UART5 (User, DMA-enabled)
|
||||
- SERIAL6 -> UART6 (RCIN, DMA-enabled)
|
||||
- SERIAL7 -> UART7 (RX only, ESC Telemetry, DMA-enabled)
|
||||
- SERIAL8 -> UART8 (MAVLink2, connected to on board BlueTooth module)
|
||||
|
||||
|
||||
## RC Input
|
||||
|
||||
The UART6 is compatible with all ArduPilot supported receiver protocols,
|
||||
|
||||
* PPM is not supported.
|
||||
|
||||
* SBUS/DSM/SRXL connects to the RX6 pin.
|
||||
|
||||
* FPort requires connection to TX6 . See FPort Receivers.
|
||||
|
||||
* CRSF also requires a TX6 connection, in addition to RX6, and automatically provides telemetry.
|
||||
|
||||
* SRXL2 requires a connection to TX6 and automatically provides telemetry. Set SERIAL6_OPTIONS to “4”.
|
||||
|
||||
Any UART can also be used for RC system connections in ArduPilot and is compatible with all protocols except PPM. See Radio Control Systems for details.
|
||||
|
||||
## OSD Support
|
||||
|
||||
The MicoAir743v2 supports onboard OSD using OSD_TYPE 1 (MAX7456 driver). Simultaneously, DisplayPort OSD is available on the HD VTX connector, set OSD_TYPE2 = "5".
|
||||
|
||||
|
||||
## VTX Support
|
||||
|
||||
The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The MicoAir743v2 supports up to 11 PWM outputs.
|
||||
|
||||
All the channels support DShot.
|
||||
|
||||
Channels 1-8 support bi-directional DShot.
|
||||
|
||||
PWM outputs are grouped and every group must use the same output protocol:
|
||||
|
||||
1, 2, 3, 4 are Group 1;
|
||||
|
||||
5, 6 are Group 2;
|
||||
|
||||
7, 8, 11 are Group 3;
|
||||
|
||||
9, 10 are Group 4;
|
||||
Note: PWM11 is the "LED" pin. If this is configured for serial LED use then PWM 7 and 8 can only be used as serial LED also.
|
||||
|
||||
## 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 10
|
||||
- BATT_CURR_PIN 11
|
||||
- BATT_VOLT_MULT 21.12
|
||||
- BATT_CURR_SCALE 40.2
|
||||
|
||||
## Compass
|
||||
|
||||
The MicoAir743v2 has a built-in compass sensor (QMC5883L), and you can also attach an external compass using I2C on the SDA and SCL connector.
|
||||
|
||||
## BlueTooth
|
||||
|
||||
The MicoAir743v2 has an on board BlueTooth module connected to UART8(SERIAL8). The BlueTooth id is MicoAir743v2-xxxxxx and you can connect to it without pairing id.
|
||||
|
||||
## Mechanical
|
||||
|
||||
- Mounting: 30.5 x 30.5mm, Φ4mm
|
||||
- Dimensions: 36 x 36 x 8 mm
|
||||
- Weight: 10g
|
||||
|
||||
## Ports Connector
|
||||
|
||||
![MicoAir H743 v2.0 Ports Connection](MicoAir743v2_Ports_Connection.jpg)
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
Initial firmware load can be done with DFU by plugging in USB with the bootloader button pressed. Then you should load the "XXXX_with_bl.hex" firmware, using your favorite DFU loading tool.
|
||||
|
||||
|
||||
Once the initial firmware is loaded you can update the firmware using any ArduPilot ground station software. Updates should be done with the "\*.apj" firmware files.
|
||||
|
46
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/hwdef-bl.dat
Normal file
46
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/hwdef-bl.dat
Normal file
@ -0,0 +1,46 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for the MicoAir743 hardware
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_MicoAir743v2
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART1
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# pins for SWD debugging
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# CS pins
|
||||
PD5 BMI088_G_CS CS
|
||||
PD4 BMI088_A_CS CS
|
||||
PA15 BMI270_CS CS
|
||||
PB12 AT7456E_CS CS
|
||||
|
||||
# LEDs
|
||||
PE2 LED_ACTIVITY OUTPUT LOW #green
|
||||
PE4 LED_BOOTLOADER OUTPUT LOW #blue
|
||||
define HAL_LED_ON 0
|
176
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/hwdef.dat
Normal file
176
libraries/AP_HAL_ChibiOS/hwdef/MicoAir743v2/hwdef.dat
Normal file
@ -0,0 +1,176 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for the MicoAir743v2 hardware
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_MicoAir743v2
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 12
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
STORAGE_FLASH_PAGE 14
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# UARTs
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
PD8 USART3_TX USART3
|
||||
PD9 USART3_RX USART3
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
PB6 UART5_TX UART5
|
||||
PB5 UART5_RX UART5
|
||||
PC6 USART6_TX USART6
|
||||
PC7 USART6_RX USART6
|
||||
PE8 UART7_TX UART7
|
||||
PE7 UART7_RX UART7
|
||||
PE1 UART8_TX UART8
|
||||
PE0 UART8_RX UART8
|
||||
|
||||
# SWD
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# order of I2C
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# I2C
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
# PWM
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) BIDIR
|
||||
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR
|
||||
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
||||
PB1 TIM3_CH4 TIM3 PWM(5) GPIO(54) BIDIR
|
||||
PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55)
|
||||
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR
|
||||
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57)
|
||||
PE5 TIM15_CH1 TIM15 PWM(9) GPIO(58)
|
||||
PE6 TIM15_CH2 TIM15 PWM(10) GPIO(59)
|
||||
|
||||
# LED-pad
|
||||
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) #M11
|
||||
|
||||
# BUZZER
|
||||
PD15 BUZZER OUTPUT GPIO(61) LOW
|
||||
define HAL_BUZZER_PIN 61
|
||||
|
||||
# 11 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 11
|
||||
|
||||
# LEDs
|
||||
PE3 LED_RED OUTPUT LOW GPIO(0)
|
||||
PE2 LED_GREEN OUTPUT LOW GPIO(1)
|
||||
PE4 LED_BLUE OUTPUT LOW GPIO(2)
|
||||
|
||||
define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0
|
||||
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1
|
||||
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2
|
||||
|
||||
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
|
||||
|
||||
# ADC for Power
|
||||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# setup for battery
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 10
|
||||
define HAL_BATT_CURR_PIN 11
|
||||
define HAL_BATT_VOLT_SCALE 21.12
|
||||
define HAL_BATT_CURR_SCALE 40.2
|
||||
|
||||
# compass
|
||||
define HAL_COMPASS_DISABLE_QMC5883L_INTERNAL_PROBE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
COMPASS QMC5883L I2C:ALL_EXTERNAL:0x0D true ROTATION_NONE
|
||||
COMPASS QMC5883L I2C:ALL_INTERNAL:0x0D false ROTATION_NONE
|
||||
|
||||
# microSD support
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
define FATFS_HAL_DEVICE SDCD1
|
||||
|
||||
# SPI1 - OSD
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
PB12 AT7456E_CS CS
|
||||
|
||||
# SPI2 - BMI088
|
||||
PD3 SPI2_SCK SPI2
|
||||
PC2 SPI2_MISO SPI2
|
||||
PC3 SPI2_MOSI SPI2
|
||||
PD5 BMI088_G_CS CS
|
||||
PD4 BMI088_A_CS CS
|
||||
PC15 DRDY1_BMI088_G INPUT
|
||||
PC14 DRDY2_BMI088_A INPUT
|
||||
|
||||
# SPI3 - BMI270
|
||||
PB3 SPI3_SCK SPI3
|
||||
PB4 SPI3_MISO SPI3
|
||||
PD6 SPI3_MOSI SPI3
|
||||
PA15 BMI270_CS CS
|
||||
PB7 DRDY3_BMI270 INPUT
|
||||
|
||||
# SPI devices
|
||||
SPIDEV bmi088_a SPI2 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_g SPI2 DEVID2 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi270 SPI3 DEVID3 BMI270_CS MODE3 1*MHZ 10*MHZ
|
||||
SPIDEV osd SPI1 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
# 2 IMUs
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_270
|
||||
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
||||
|
||||
# barometers
|
||||
BARO SPL06 I2C:0:0x77
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
# setup for serial ports
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MSP_DisplayPort
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
|
||||
define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_MAVLink2
|
||||
define DEFAULT_SERIAL8_BAUD 115
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# setup for BF migration
|
||||
define HAL_FRAME_TYPE 12
|
Loading…
Reference in New Issue
Block a user