forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 11
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
AP_HAL_ChibiOS: add hwdef for Here4FC
- Loading branch information
1 parent
5d4c99d
commit 641468c
Showing
3 changed files
with
211 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,12 @@ | ||
# setup for ProfiLED | ||
SERVO9_FUNCTION 132 | ||
SERVO10_FUNCTION 129 | ||
NTF_LED_TYPES 512 | ||
NTF_LED_BRIGHT 2 | ||
NTF_LED_LEN 4 | ||
|
||
# Disable Logging by default | ||
LOG_BACKEND_TYPE 0 | ||
|
||
# make node id to not conflict with ardupilot default | ||
CAN_D1_UC_NODE 8 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
# hw definition file for processing by chibios_hwdef.py | ||
# for H757 bootloader | ||
|
||
# MCU class and specific type | ||
MCU STM32H7xx STM32H757xx | ||
|
||
define CORE_CM7 | ||
define SMPS_PWR | ||
|
||
# setup build for a peripheral firmware | ||
env AP_PERIPH 1 | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 24000000 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 1043 | ||
|
||
FLASH_SIZE_KB 2048 | ||
|
||
# bootloader is installed at zero offset | ||
FLASH_RESERVE_START_KB 0 | ||
|
||
# reserve space for flash storage in last 2 sectors | ||
FLASH_RESERVE_END_KB 256 | ||
|
||
# the location where the bootloader will put the firmware | ||
# the H757 has 128k sectors | ||
FLASH_BOOTLOADER_LOAD_KB 256 | ||
|
||
# enable CAN support | ||
PD0 CAN1_RX CAN1 | ||
PD1 CAN1_TX CAN1 | ||
PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW | ||
PD3 TERMCAN1 OUTPUT LOW | ||
|
||
PB12 CAN2_RX CAN2 | ||
PB13 CAN2_TX CAN2 | ||
PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW LOW | ||
PB11 TERMCAN2 OUTPUT LOW | ||
|
||
# board voltage | ||
STM32_VDD 330U | ||
|
||
PB8 LED_SCK OUTPUT LOW | ||
PB9 LED_DI OUTPUT HIGH | ||
|
||
define HAL_NO_LOGGING TRUE | ||
define HAL_NO_MONITOR_THREAD | ||
|
||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
define AP_PERIPH_HAVE_LED | ||
|
||
define CAN_APP_NODE_NAME "com.cubepilot.here4fc" | ||
|
||
PB6 USART1_TX USART1 | ||
PB7 USART1_RX USART1 | ||
|
||
PE0 UART8_RX UART8 | ||
PE1 UART8_TX UART8 | ||
|
||
# order of UARTs | ||
SERIAL_ORDER USART1 UART8 | ||
|
||
# setup for blanking LEDs in bootloader | ||
define AP_BOOTLOADER_CUSTOM_HERE4 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,131 @@ | ||
# hw definition file for processing by chibios_hwdef.py | ||
# for H757 | ||
|
||
# MCU class and specific type | ||
MCU STM32H7xx STM32H757xx | ||
|
||
define CORE_CM7 | ||
define SMPS_PWR | ||
|
||
FLASH_SIZE_KB 2048 | ||
APJ_BOARD_ID 1043 | ||
|
||
|
||
# the location where the bootloader will put the firmware | ||
# the H757 has 128k sectors | ||
FLASH_BOOTLOADER_LOAD_KB 256 | ||
FLASH_RESERVE_START_KB 256 | ||
|
||
# use last 2 pages for flash storage | ||
# H757 has 16 pages of 128k each | ||
STORAGE_FLASH_PAGE 14 | ||
define HAL_STORAGE_SIZE 32768 | ||
|
||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 24000000 | ||
|
||
CANFD_SUPPORTED 8 | ||
|
||
STDOUT_SERIAL SD6 | ||
STDOUT_BAUDRATE 57600 | ||
|
||
PC6 USART6_TX USART6 | ||
|
||
PB6 USART1_TX USART1 GPIO(7) | ||
PB7 USART1_RX USART1 GPIO(8) | ||
|
||
PD5 USART2_TX USART2 GPIO(9) | ||
PD6 USART2_RX USART2 GPIO(10) | ||
|
||
PA11 UART4_RX UART4 | ||
PA12 UART4_TX UART4 | ||
|
||
define GPIO_USART1_TX 7 | ||
define GPIO_USART1_RX 8 | ||
define GPIO_USART2_TX 9 | ||
define GPIO_USART2_RX 10 | ||
|
||
PE0 UART8_RX UART8 | ||
PE1 UART8_TX UART8 | ||
|
||
SERIAL_ORDER USART1 UART4 UART8 USART2 | ||
|
||
define DRONEID_MODULE_PORT 2 | ||
define DRONEID_MODULE_CHAN MAVLINK_COMM_0 | ||
|
||
define AP_UART_MONITOR_ENABLED 1 | ||
|
||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
|
||
# RCInput | ||
PB15 TIM12_CH2 TIM12 RCININT PULLDOWN LOW | ||
|
||
# RCOutput | ||
PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR | ||
PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) # shared with channel 1 | ||
PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR | ||
PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) # shared with channel 3 | ||
PC7 TIM3_CH2 TIM3 PWM(5) GPIO(54) BIDIR | ||
PC8 TIM3_CH3 TIM3 PWM(6) GPIO(55) BIDIR | ||
PC9 TIM3_CH4 TIM3 PWM(7) GPIO(56) BIDIR | ||
PA3 TIM2_CH4 TIM2 PWM(8) GPIO(57) BIDIR | ||
|
||
# enable CAN support | ||
PD0 CAN1_RX CAN1 | ||
PD1 CAN1_TX CAN1 | ||
PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW | ||
PD3 TERMCAN1 OUTPUT HIGH GPIO(3) | ||
|
||
PE7 UART7_RX UART7 | ||
PE8 UART7_TX UART7 | ||
|
||
PB12 CAN2_RX CAN2 | ||
PB13 CAN2_TX CAN2 | ||
PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW LOW | ||
PB11 TERMCAN2 OUTPUT HIGH GPIO(4) | ||
|
||
define AP_OPENDRONEID_ENABLED 1 | ||
|
||
PB3 SPI3_SCK SPI3 | ||
PB4 SPI3_MISO SPI3 | ||
PB2 SPI3_MOSI SPI3 | ||
PB1 MAG_CS CS | ||
|
||
SPIDEV rm3100 SPI3 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ | ||
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 | ||
define AP_RM3100_REVERSAL_MASK 4 | ||
|
||
# HOTSHOE pin repurposed for BATT Voltage Sens | ||
PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) | ||
|
||
PA8 ICM_CS CS | ||
PA9 BARO_CS CS | ||
PA5 SPI1_SCK SPI1 | ||
PA6 SPI1_MISO SPI1 | ||
PA7 SPI1_MOSI SPI1 | ||
SPIDEV icm42688 SPI1 DEVID4 ICM_CS MODE3 2*MHZ 8*MHZ | ||
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ | ||
|
||
BARO MS56XX SPI:ms5611 | ||
|
||
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_270 | ||
|
||
define HAL_DEFAULT_INS_FAST_SAMPLE 5 | ||
|
||
# WS2812 LED | ||
PB8 TIM4_CH3 TIM4 PWM(9) | ||
PB9 TIM4_CH4 TIM4 PWM(10) | ||
|
||
PD11 GPS_TP1 OUTPUT LOW GPIO(5) | ||
PD7 GPS_PPS INPUT PULLUP GPIO(6) | ||
define CONFIGURE_PPS_PIN TRUE | ||
define HAL_GPIO_PPS 6 | ||
|
||
PD12 GPS_SAFEBOOT_N INPUT FLOATING GPIO(11) | ||
define GPIO_UBX_SAFEBOOT 11 | ||
PD13 GPS_RESET_N INPUT FLOATING GPIO(12) | ||
define GPIO_UBX_RESET 12 | ||
define HAL_EARLY_WATCHDOG_INIT |