mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add hwdef files for Airvolute DCS2 onboard FMU
added ethernet config to hwdef updated readme.md hwdef: MAC parameters redefined according to ChibiOS hwdef: add default params for Airvolute DCS2 on board FMU update according to new changes in ChibiOS MAC driver added defines to support ethernet communication bootloaders: Airvolute-DCS2
This commit is contained in:
parent
f8d7be5e43
commit
e6feebb2fb
Binary file not shown.
After Width: | Height: | Size: 238 KiB |
Binary file not shown.
After Width: | Height: | Size: 559 KiB |
Binary file not shown.
After Width: | Height: | Size: 597 KiB |
|
@ -0,0 +1,256 @@
|
|||
# Onboard FMU on Airvolute DCS2.Pilot board
|
||||
|
||||
DroneCore 2.0 is a modular AI-driven open architecture autopilot designed for complex use cases that combines high computational processing power, redundant connectivity, small size, and low weight.The autopilot represents a one-stop-solution for developers integrating the functionality of carrier board, companion computer, and power distribution board into a single compact form factor.
|
||||
This system usually uses a "CUBE" autopilot as its primary FMU, but can use an onboard STM32H743 as the FMU. This board definition and firmware on `the ArduPilot firmware server <https://firmware.ardupilot.org>`__ is for this secondary FMU
|
||||
For more informations on DCS2.Pilot board see:
|
||||
https://docs.airvolute.com/dronecore-autopilot/dcs2
|
||||
|
||||
## Where To Buy
|
||||
info@airvolute.com
|
||||
|
||||
## Features
|
||||
|
||||
- MCU: STM32H743
|
||||
- IMU: BMI088
|
||||
- Barometer: BMP390
|
||||
- 2 UARTS
|
||||
- 2 CAN buses
|
||||
- 4 PWM outputs
|
||||
- PPM (RC input)
|
||||
- external SPI and I2C
|
||||
- SD card connector
|
||||
- USB connection onboard with Jetson Host
|
||||
- Ethernet
|
||||
|
||||
## DCS2.Pilot peripherals diagram
|
||||
<img width="957" alt="DC2 Pilot peripherals" src="https://github.com/vrsanskytom/ardupilot/blob/hwdef_for_airvolute_dcs2/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DC2.Pilot%20peripherals.png">
|
||||
|
||||
## DCS2.Pilot onboard FMU related connectors pinout
|
||||
### Top side
|
||||
<img width="818" alt="DCS2 Pilot_bottom" src="https://github.com/vrsanskytom/ardupilot/blob/hwdef_for_airvolute_dcs2/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_TopSide.png">
|
||||
|
||||
#### <ins>PPM connector (RC input)</ins>
|
||||
JST GH 1.25mm pitch, 3-Pin
|
||||
|
||||
Matching connector JST GHR-03V-S.
|
||||
|
||||
RC input is configured on the PPM_SBUS_PROT pin as part of the PPM connector. Pin is connected to UART3_RX and also to analog input on TIM3_CH1. This pin supports all unidirectional RC protocols, but for it to be enabled, it is necessary to set SERIAL3_PROTOCOL as RCIN. Also RC input is shared with primary FMU, so it is default disabled on this secondary FMU.
|
||||
|
||||
5V supply is limited to 1A by internal current limiter.
|
||||
<table border="1" class="docutils">
|
||||
<tbody>
|
||||
<tr>
|
||||
<th>Pin </th>
|
||||
<th>Signal </th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>1</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<td>2</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
<td>3</td>
|
||||
<td>PPM</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
### Bottom side
|
||||
<img width="811" alt="DCS2 Pilot_top" src="https://github.com/vrsanskytom/ardupilot/blob/hwdef_for_airvolute_dcs2/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_BottomSide.png">
|
||||
|
||||
#### <ins>FMU SEC. connector</ins>
|
||||
JST GH 1.25mm pitch, 12-Pin
|
||||
|
||||
Matching connector JST GHR-12V-S.
|
||||
|
||||
The DCS2 Onboard FMU supports up to 4 PWM outputs. These are directly attached to the STM32H743 and support all PWM protocols as well as DShot and bi-directional DShot.
|
||||
The 4 PWM outputs are in 2 groups:
|
||||
PWM 1,2 in group1
|
||||
PWM 3,4 in group2
|
||||
Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need to use DShot.
|
||||
|
||||
5V supply is limited to 1A by internal current limiter.
|
||||
<table border="1" class="docutils">
|
||||
<tbody>
|
||||
<tr>
|
||||
<th>Pin </th>
|
||||
<th>Signal </th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>1</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<td>2</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
<td>3</td>
|
||||
<td>GPIO/PWM output 4</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>4</td>
|
||||
<td>GPIO/PWM output 3</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>5</td>
|
||||
<td>GPIO/PWM output 2</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>6</td>
|
||||
<td>GPIO/PWM output 1</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>7</td>
|
||||
<td>Serial 1 RX</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>8</td>
|
||||
<td>Serial 1 TX</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>9</td>
|
||||
<td>Serial 2 RX</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>10</td>
|
||||
<td>Serial 2 TX</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>11</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>12</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
#### <ins>EXT. SENS. connector</ins>
|
||||
BM23PF0.8-10DS-0.35V connector
|
||||
|
||||
Matching connector BM23PF0.8-10DP-0.35V
|
||||
|
||||
This connector allows connecting external IMU with I2C and SPI data buses.
|
||||
|
||||
5V supply is limited to 1.9A by internal current limiter.
|
||||
<table border="1" class="docutils">
|
||||
<tbody>
|
||||
<tr>
|
||||
<th>Pin </th>
|
||||
<th>Signal </th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>1</td>
|
||||
<td>SPI_MOSI</td>
|
||||
</tr>
|
||||
<td>2</td>
|
||||
<td>SPI_MISO</td>
|
||||
</tr>
|
||||
<td>3</td>
|
||||
<td>SPI_SCK</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>4</td>
|
||||
<td>SPI_CS0</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>5</td>
|
||||
<td>SPI_CS1</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>6</td>
|
||||
<td>SPI_CS2</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>7</td>
|
||||
<td>SPI_CS3</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>8</td>
|
||||
<td>IMU_DRDY_EXT</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>9</td>
|
||||
<td>I2C_SE_SDA</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>10</td>
|
||||
<td>I2C_SE_SCL</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>MP1</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>MP2</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>MP3</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tr>
|
||||
<td>MP4</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
#### <ins>ETH EXP. connector</ins>
|
||||
505110-1692 connector
|
||||
|
||||
Ethernet connector is routed to FMU through onboard switch.
|
||||
|
||||
The onboard FMU is connected via the RMII bus with a speed of 100 Mbits.
|
||||
|
||||
#### <ins>SD card connector</ins>
|
||||
MEM2085-00-115-00-A connector
|
||||
|
||||
Connector for standard microSD memory card. This card is primarily used to store flight data and logs.
|
||||
|
||||
## Other connectors
|
||||
### CAN 1, CAN 2 connectors
|
||||
The board contains two CAN buses - CAN1 and CAN 2. The buses support speeds up to 1 Mbits and in FD mode up to 8 Mbits.
|
||||
|
||||
These connectors are not part of DCS2.Pilot board, but they are routed on DCS2.Adapter_board. This board (DCS2.Adapter_board) is fully modular and can be modified according to the customer's requirements. For more informations see: https://docs.airvolute.com/dronecore-autopilot/dcs2/adapter-extension-boards/dcs2.-adapter-default-v1.0/connectors-and-pinouts
|
||||
|
||||
JST GH 1.25mm pitch, 4-Pin
|
||||
|
||||
Matching connector JST GHR-04V-S.
|
||||
|
||||
5V supply is limited to 1.9A by internal current limiter.
|
||||
<table border="1" class="docutils">
|
||||
<tbody>
|
||||
<tr>
|
||||
<th>Pin </th>
|
||||
<th>Signal </th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>1</td>
|
||||
<td>5V</td>
|
||||
</tr>
|
||||
<td>2</td>
|
||||
<td>CAN_H</td>
|
||||
</tr>
|
||||
<td>3</td>
|
||||
<td>CAN_L</td>
|
||||
</tr>
|
||||
<td>4</td>
|
||||
<td>GND</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB (Default baud: 115200)
|
||||
- SERIAL1 -> UART1 (FMU SEC) (Default baud: 57600, Default protocol: Mavlink2 (2))
|
||||
- SERIAL2 -> UART2 (FMU SEC) (Default baud: 57600, Default protocol: Mavlink2 (2))
|
||||
- SERIAL3 -> UART3 (RX pin only labeled as PPM on PPM connector) (Since this is a secondary FMU, default protocol is set to NONE instead of RCIN (23))
|
||||
|
||||
UARTs do not have RTS/CTS. UARTs 1 and 2 are routed to FMU_SEC. connector.
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
Initial bootloader load is achievable only by SDW interface. Then it is possible to flash firmware thrugh onboard USB connection with Jetson host.
|
|
@ -0,0 +1,4 @@
|
|||
SERIAL3_PROTOCOL -1
|
||||
NTF_BUZZ_TYPES 0
|
||||
NTF_BUZZ_VOLUME 0
|
||||
SYSID_THISMAV 2
|
|
@ -0,0 +1,58 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for H743 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 5200
|
||||
|
||||
# the nucleo seems to have trouble with flashing the last sector?
|
||||
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
|
||||
|
||||
# USB setup
|
||||
USB_STRING_MANUFACTURER "Airvolute"
|
||||
|
||||
# baudrate to run bootloader at on uarts
|
||||
define BOOTLOADER_BAUDRATE 115200
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1
|
||||
|
||||
# this is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
|
||||
# UART1 (SE_CONNECTOR)
|
||||
PB14 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
PB1 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 1
|
||||
|
||||
define HAL_USE_SERIAL TRUE
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PD12 IMU_CS0 CS
|
||||
PE13 IMU_CS1 CS
|
||||
PD13 BARO_CS CS
|
||||
PD15 EXT_0 CS
|
||||
PD14 EXT_1 CS
|
||||
PD11 EXT_2 CS
|
||||
PD10 EXT_3 CS
|
|
@ -0,0 +1,174 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
#following exapmle:
|
||||
#https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroH7/hwdef.dat#L105
|
||||
# for H743 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 5200
|
||||
|
||||
# the nucleo seems to have trouble with flashing the last sector?
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# This is the STM32 timer that ChibiOS will use for the low level
|
||||
# driver. This must be a 32 bit timer. We currently only support
|
||||
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details.
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
#optimize for space
|
||||
env OPTIMIZE -Os
|
||||
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
|
||||
# use last 2 pages for flash storage
|
||||
# H743 has 16 pages of 128k each
|
||||
STORAGE_FLASH_PAGE 14
|
||||
|
||||
# (---FUTURE REVISION---): PA0 AS VDD_SENSE_PIN
|
||||
PA0 VDD_5V_SENS ADC1 SCALE(2)
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# I2C1 (SE_CONNECTOR)
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
PB7 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
# USB setup
|
||||
USB_STRING_MANUFACTURER "Airvolute"
|
||||
|
||||
# This is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN.
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# (---FUTURE REVISION---): PWM output for buzzer
|
||||
PB15 TIM12_CH2 TIM12 GPIO(80) ALARM
|
||||
|
||||
# (---FUTURE REVISION---): RC Input set for Interrupt not DMA
|
||||
PA6 TIM3_CH1 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# UART SETUP
|
||||
# USART1 (SE_CONNECTOR)
|
||||
PB14 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# USART2 (SE_CONNECTOR)
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
# USART3 (RC INPUT)
|
||||
PD9 USART3_RX USART3
|
||||
|
||||
#LED RED
|
||||
PB1 LED1 OUTPUT HIGH
|
||||
#LED GREEN
|
||||
PA3 FMU_LED_AMBER OUTPUT LOW GPIO(0)
|
||||
|
||||
# microSD card
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# CS pins for SPI sensors. The labels for all CS pins need to
|
||||
# match the SPI device table later in this file.
|
||||
PD12 BMI088_ACC_CS CS
|
||||
PE13 BMI088_GYRO_CS CS
|
||||
PD13 BMP390_CS CS
|
||||
PD15 EXT_0_CS CS
|
||||
PD14 EXT_1_CS CS
|
||||
PD11 EXT_2_CS CS
|
||||
PD10 EXT_3_CS CS
|
||||
|
||||
# CAN Busses
|
||||
PD0 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
# CAN1 Silent Pin LOW Enable
|
||||
PC7 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
|
||||
PB5 CAN2_RX CAN2
|
||||
PB6 CAN2_TX CAN2
|
||||
|
||||
# CAN2 Silent Pin LOW Enable
|
||||
PC6 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
|
||||
|
||||
# Ethernet
|
||||
PC1 ETH_MDC ETH1
|
||||
PA2 ETH_MDIO ETH1
|
||||
PC4 ETH_RMII_RXD0 ETH1
|
||||
PC5 ETH_RMII_RXD1 ETH1
|
||||
PB12 ETH_RMII_TXD0 ETH1
|
||||
PB13 ETH_RMII_TXD1 ETH1
|
||||
PB11 ETH_RMII_TX_EN ETH1
|
||||
PA7 ETH_RMII_CRS_DV ETH1
|
||||
PA1 ETH_RMII_REF_CLK ETH1
|
||||
|
||||
define BOARD_PHY_RMII
|
||||
define BOARD_PHY_ADDRESS 0x0000
|
||||
define STM32_MAC_PHY_LINK_TYPE MAC_LINK_100_FULLDUPLEX
|
||||
define HAL_PERIPH_ENABLE_NETWORKING
|
||||
|
||||
#PWM outputs
|
||||
PB3 TIM2_CH2 TIM2 PWM(1) GPIO(50) BIDIR
|
||||
PB10 TIM2_CH3 TIM2 PWM(2) GPIO(51)
|
||||
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR
|
||||
PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53)
|
||||
|
||||
# BMI088_DRDY
|
||||
PE12 BMI088_DRDY INPUT
|
||||
|
||||
# (---FUTURE REVISION---) EXT IMU DRDY
|
||||
PD1 EXT_IMU_DRDY INPUT
|
||||
|
||||
# SPI1 (ONBOARD SENSORS)
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB4 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI4 (EXTERNAL SENSORS)
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE5 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# SPI devices
|
||||
SPIDEV bmi088_g SPI1 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_a SPI1 DEVID2 BMI088_ACC_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmp390 SPI1 DEVID3 BMP390_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV icm42688_ext SPI4 DEVID4 EXT_0_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV lis3mdl SPI4 DEVID5 EXT_1_CS MODE3 5*MHZ 5*MHZ
|
||||
|
||||
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
# IMUs
|
||||
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE
|
||||
IMU Invensense SPI:icm42688_ext ROTATION_NONE
|
||||
|
||||
# 1 baro
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO 1
|
||||
BARO BMP388 SPI:bmp390
|
||||
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
Loading…
Reference in New Issue