forked from tridge/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
9dca511
commit 9120a36
Showing
3 changed files
with
177 additions
and
0 deletions.
There are no files selected for viewing
4 changes: 4 additions & 0 deletions
4
libraries/AP_HAL_ChibiOS/hwdef/sw-universal-payload/defaults.parm
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,4 @@ | ||
BATT_MONITOR 3 | ||
BATT_VOLT_PIN 1 | ||
EFI_TYPE 1 | ||
RNGFND1_TYPE 8 |
37 changes: 37 additions & 0 deletions
37
libraries/AP_HAL_ChibiOS/hwdef/sw-universal-payload/hwdef-bl.dat
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,37 @@ | ||
# MCU class and specific type | ||
MCU STM32F4xx STM32F407xx | ||
|
||
FLASH_RESERVE_START_KB 0 | ||
FLASH_BOOTLOADER_LOAD_KB 64 | ||
FLASH_SIZE_KB 512 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 6000 | ||
|
||
env AP_PERIPH 1 | ||
|
||
define CAN_APP_NODE_NAME "sw-spar-f407-bl" | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
# activity led | ||
PC8 LED_BOOTLOADER OUTPUT LOW | ||
define HAL_LED_ON 1 | ||
|
||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# ECU - we don't use this at the moment, but it must be enabled for CAN2 to work | ||
PD0 CAN1_RX CAN1 | ||
PD1 CAN1_TX CAN1 | ||
PD2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH | ||
|
||
# Avionics | ||
PB5 CAN2_RX CAN2 | ||
PB6 CAN2_TX CAN2 | ||
PB7 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW | ||
|
||
PA11 OTG_FS_DM OTG1 | ||
PA12 OTG_FS_DP OTG1 | ||
SERIAL_ORDER OTG1 |
136 changes: 136 additions & 0 deletions
136
libraries/AP_HAL_ChibiOS/hwdef/sw-universal-payload/hwdef.dat
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,136 @@ | ||
# MCU class and specific type | ||
MCU STM32F4xx STM32F407xx | ||
|
||
FLASH_RESERVE_START_KB 64 | ||
FLASH_SIZE_KB 512 | ||
|
||
define HAL_STORAGE_SIZE 15360 | ||
STORAGE_FLASH_PAGE 2 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 6085 | ||
|
||
env AP_PERIPH 1 | ||
|
||
define CAN_APP_NODE_NAME "sw-universal-payload-f407" | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
# we need tim2 for PWM | ||
STM32_ST_USE_TIMER 5 | ||
|
||
# activity led | ||
PC8 LED OUTPUT LOW | ||
define HAL_LED_ON 1 | ||
|
||
# JTAG | ||
#PA13 JTMS-SWDIO SWD | ||
#PA14 JTCK-SWCLK SWD | ||
|
||
# CAN | ||
PD0 CAN1_RX CAN1 | ||
PD1 CAN1_TX CAN1 | ||
PD7 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH | ||
|
||
# ---------------------- UARTs --------------------------- | ||
SERIAL_ORDER USART1 USART2 USART3 | ||
|
||
# USART1 | ||
PA9 USART1_TX USART1 SPEED_HIGH DMA | ||
PA10 USART1_RX USART1 SPEED_HIGH DMA | ||
|
||
# USART2 | ||
PD3 USART2_CTS USART2 | ||
PD4 USART2_RTS USART2 | ||
PD5 USART2_TX USART2 SPEED_HIGH DMA | ||
PD6 USART2_RX USART2 SPEED_HIGH DMA | ||
|
||
# USART3 | ||
PB10 USART3_TX USART3 SPEED_HIGH DMA | ||
PB11 USART3_RX USART3 SPEED_HIGH DMA | ||
|
||
# UART5 | ||
PC12 UART5_TX UART5 SPEED_HIGH DMA | ||
PD2 UART5_RX UART5 SPEED_HIGH DMA | ||
|
||
PE9 5V_PAYLOAD_SW_ENABLE OUTPUT GPIO(1) PUSHPULL SPEED_LOW HIGH | ||
PE11 RELAY_1 OUTPUT GPIO(2) PUSHPULL SPEED_LOW HIGH | ||
PE12 RELAY_2 OUTPUT GPIO(3) PUSHPULL SPEED_LOW HIGH | ||
PE13 RELAY_3 OUTPUT GPIO(4) PUSHPULL SPEED_LOW HIGH | ||
PE14 28V_PAYLOAD_SW_ENABLE OUTPUT GPIO(5) PUSHPULL SPEED_LOW HIGH | ||
|
||
# relay outputs | ||
define HAL_PERIPH_ENABLE_RELAY 1 | ||
define AP_RELAY_ENABLED 1 | ||
define RELAY1_PIN_DEFAULT 1 | ||
define RELAY2_PIN_DEFAULT 2 | ||
define RELAY3_PIN_DEFAULT 3 | ||
define RELAY4_PIN_DEFAULT 4 | ||
define RELAY5_PIN_DEFAULT 5 | ||
|
||
# don't build on firmware.ardupilot.org | ||
# i2c | ||
I2C_ORDER I2C3 | ||
define STM32_I2C_USE_I2C3 TRUE | ||
define HAL_I2C_CLEAR_ON_TIMEOUT 0 | ||
define HAL_I2C_INTERNAL_MASK 0 | ||
|
||
# internal mag | ||
PA8 I2C3_SCL I2C3 | ||
PC9 I2C3_SDA I2C3 | ||
|
||
# GPS | ||
define HAL_PERIPH_ENABLE_GPS | ||
define HAL_PERIPH_GPS_PORT_DEFAULT 1 | ||
define GPS_MAX_RATE_MS 200 | ||
|
||
define GPS_MAX_RECEIVERS 1 | ||
define GPS_MAX_INSTANCES 1 | ||
|
||
# rangefinder | ||
define HAL_PERIPH_ENABLE_RANGEFINDER 2 | ||
define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 | ||
|
||
# compass | ||
define HAL_PERIPH_ENABLE_MAG | ||
define HAL_COMPASS_MAX_SENSORS 2 | ||
|
||
COMPASS MMC3416 I2C:0:0x30 false ROTATION_NONE | ||
|
||
# expected aux compass, unclear if these need to be listed | ||
COMPASS RM3100 I2C:1:0x20 false ROTATION_NONE | ||
COMPASS RM3100 I2C:1:0x21 false ROTATION_NONE | ||
COMPASS RM3100 I2C:1:0x22 false ROTATION_NONE | ||
COMPASS RM3100 I2C:1:0x23 false ROTATION_NONE | ||
|
||
# battery | ||
define HAL_PERIPH_ENABLE_BATTERY | ||
define HAL_PERIPH_BATTERY_SKIP_NAME # don't waste bandwidth on static names | ||
define AP_BATT_MONITOR_MAX_INSTANCES 4 | ||
define HAL_BATT_MONITOR_DEFAULT 3 | ||
|
||
define HAL_USE_ADC TRUE | ||
define STM32_ADC_USE_ADC1 TRUE | ||
|
||
# ADC's | ||
# 5v pi sw | ||
PA6 BATT_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(1) | ||
# 5V | ||
PA7 BATT2_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(2) | ||
# 28V switchable | ||
PB0 BATT3_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(3) | ||
# VBatt | ||
PB1 BATT4_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(4) | ||
# 28V | ||
PC4 BATT5_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(5) | ||
# 5V payload switch | ||
PC5 BATT6_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(6) | ||
|
||
# don't build on firmware.ardupilot.org | ||
AUTOBUILD_TARGETS None | ||
|
||
define HAL_SERIAL_ESC_COMM_ENABLED 1 | ||
define HAL_RCIN_THREAD_ENABLED 1 | ||
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1 | ||
define HAL_MONITOR_THREAD_ENABLED 1 |