mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add MicoAir405Mini
This commit is contained in:
parent
6538e8c9ae
commit
5c4aeddae7
Binary file not shown.
After Width: | Height: | Size: 149 KiB |
Binary file not shown.
After Width: | Height: | Size: 184 KiB |
Binary file not shown.
Binary file not shown.
After Width: | Height: | Size: 285 KiB |
|
@ -0,0 +1,95 @@
|
|||
# MicoAir405Mini Flight Controller
|
||||
|
||||
The MicoAir405Mini is a flight controller designed and produced by [MicoAir Tech.](http://micoair.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32F405 microcontroller
|
||||
- BMI270 IMU
|
||||
- DPS310 barometer
|
||||
- AT7456E OSD
|
||||
- 9V 2.5A BEC; 5V 2.5A BEC
|
||||
- SDCard
|
||||
- 6 UARTs
|
||||
- 9 PWM outputs
|
||||
|
||||
## Physical
|
||||
|
||||
![MicoAir F405 Mini V2.1 Front View](MicoAir405Mini_FrontView.jpg)
|
||||
|
||||
![MicoAir F405 Mini V2.1 Back View](MicoAir405Mini_BackView.jpg)
|
||||
|
||||
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (MAVLink2, DMA-enabled)
|
||||
- SERIAL2 -> UART2 (DisplayPort, TX only is DMA Enabled)
|
||||
- SERIAL3 -> UART3 (GPS)
|
||||
- SERIAL4 -> UART4 (MAVLink2, TX only is DMA Enabled)
|
||||
- SERIAL5 -> UART5 (ESC Telemetry)
|
||||
- SERIAL6 -> UART6 (RX6 is inverted from SBUS pin, RX only is DMA Enabled)
|
||||
|
||||
## RC Input
|
||||
|
||||
The default RC input is configured as SBUS via the SBUS pin. Other RC protocols should be applied at a UART port such as UART1 or UART4, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL6 _Protocol to something other than '23'
|
||||
|
||||
## OSD Support
|
||||
|
||||
The MicoAir405Mini supports onboard OSD using OSD_TYPE 1 (MAX7456 driver).
|
||||
|
||||
## VTX Support
|
||||
|
||||
The SH1.0-6P connector supports a DJI O3 Air Unit connection. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The MicoAir405Mini supports up to 9 PWM outputs.
|
||||
|
||||
Channels 1-8 support DShot.
|
||||
|
||||
Channels 1-4 support bi-directional DShot.
|
||||
|
||||
PWM outputs are grouped and every group must use the same output protocol:
|
||||
|
||||
3, 4 are Group 1;
|
||||
|
||||
1, 2, 5, 6 are Group 2;
|
||||
|
||||
7, 8 are Group 3;
|
||||
|
||||
9 is in Group 4;
|
||||
|
||||
## 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.2
|
||||
- BATT_CURR_SCALE 40.2
|
||||
|
||||
## Compass
|
||||
|
||||
The MicoAir405Mini does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL connector.
|
||||
|
||||
## Mechanical
|
||||
|
||||
- Mounting: 20 x 20mm, Φ3.5mm
|
||||
- Dimensions: 30 x 30 x 8 mm
|
||||
- Weight: 6g
|
||||
|
||||
## Ports Connector
|
||||
|
||||
![MicoAir F405 Mini V2.1 Ports Connection](MicoAir405Mini_PortsConnection.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 "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.
|
|
@ -0,0 +1,14 @@
|
|||
#BATTERY MONITOR ON
|
||||
BATT_MONITOR 4
|
||||
|
||||
#enable second OSD type
|
||||
OSD_TYPE2 = 5
|
||||
|
||||
#Serial Port defaults
|
||||
SERIAL1_PROTOCOL 2
|
||||
SERIAL2_PROTOCOL 42
|
||||
SERIAL3_PROTOCOL 5
|
||||
SERIAL4_PROTOCOL 2
|
||||
SERIAL5_PROTOCOL 16
|
||||
SERIAL6_PROTOCOL 23
|
||||
GPS_DRV_OPTIONS 4
|
|
@ -0,0 +1,37 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for the MicoAir405Mini hardware
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_MicoAir405Mini
|
||||
|
||||
# crystal frequency & PPL, working at 168M
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
# chip flash size & bootloader & firmware
|
||||
FLASH_SIZE_KB 1024
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 48
|
||||
|
||||
# LEDs
|
||||
PA8 LED_BOOTLOADER OUTPUT LOW #blue
|
||||
PC4 LED_ACTIVITY OUTPUT LOW #green
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# order of UARTs and USB
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
#CS pin
|
||||
PB12 AT7456E_CS CS
|
||||
PC14 BMI270_CS CS
|
||||
PC13 DPS310_CS CS
|
||||
PC9 SDCARD_CS CS
|
|
@ -0,0 +1,150 @@
|
|||
# hw definition file for MicoAir405Mini hardware
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_MicoAir405Mini
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
STM32_PLLM_VALUE 8
|
||||
|
||||
define STM32_ST_USE_TIMER 5
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# chip flash size & bootloader & firmware
|
||||
FLASH_SIZE_KB 1024
|
||||
FLASH_RESERVE_START_KB 48
|
||||
|
||||
define HAL_STORAGE_SIZE 15360
|
||||
STORAGE_FLASH_PAGE 1
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# LEDs
|
||||
PC5 LED_RED OUTPUT LOW GPIO(0)
|
||||
PC4 LED_GREEN OUTPUT LOW GPIO(1)
|
||||
PA8 LED_BLUE OUTPUT LOW GPIO(2)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
PB6 I2C1_SCL I2C1
|
||||
PB7 I2C1_SDA I2C1
|
||||
|
||||
# spi1 bus for OSD
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# spi2 bus for IMU
|
||||
PB13 SPI2_SCK SPI2
|
||||
PC2 SPI2_MISO SPI2
|
||||
PC3 SPI2_MOSI SPI2
|
||||
|
||||
# spi3 bus for SDCARD
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PC12 SPI3_MOSI SPI3
|
||||
|
||||
#CS pin
|
||||
PB12 AT7456E_CS CS
|
||||
PC14 BMI270_CS CS
|
||||
PC13 DPS310_CS CS
|
||||
PC9 SDCARD_CS CS
|
||||
|
||||
# analog pins
|
||||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 10
|
||||
define HAL_BATT_VOLT_SCALE 21.2
|
||||
define HAL_BATT_CURR_PIN 11
|
||||
define HAL_BATT_CURR_SCALE 40.2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
# SERIAL_NUM|SER0|SER1 |SER2 |SER3 |SER4 |SER5 |SER6 |
|
||||
# FUNCTION |USB | |DJIO3 |GPS | |ESC |SBUS |
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART1
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# USART2 - DJIO3
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2 NODMA
|
||||
|
||||
# USART3 - GPS
|
||||
PB10 USART3_TX USART3 NODMA
|
||||
PB11 USART3_RX USART3 NODMA
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# UART5
|
||||
PD2 UART5_RX UART5 NODMA
|
||||
|
||||
# UART6
|
||||
PC7 USART6_RX USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC15 SBUS_INV OUTPUT
|
||||
|
||||
# 9 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 9
|
||||
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR
|
||||
PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR
|
||||
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53)
|
||||
PB4 TIM3_CH1 TIM3 PWM(5) GPIO(54)
|
||||
PB5 TIM3_CH2 TIM3 PWM(6) GPIO(55)
|
||||
PB8 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
||||
PB9 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
||||
PB14 TIM12_CH1 TIM12 PWM(9) GPIO(58) NODMA
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
# imu & baro
|
||||
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
||||
BARO DPS310 SPI:dps310
|
||||
|
||||
# SPI devices
|
||||
SPIDEV bmi270 SPI2 DEVID1 BMI270_CS MODE3 2*MHZ 10*MHZ
|
||||
SPIDEV dps310 SPI2 DEVID2 DPS310_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ
|
||||
SPIDEV osd SPI1 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
# filesystem setup on sdcard
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
||||
|
||||
# reduce flash usage
|
||||
include ../include/minimize_fpv_osd.inc
|
||||
undef AP_OPTICALFLOW_ENABLED
|
Loading…
Reference in New Issue