Skip to content

Commit

Permalink
added defaults.parm
Browse files Browse the repository at this point in the history
  • Loading branch information
dakejahl committed Dec 12, 2024
1 parent 6eb6081 commit 5df3d64
Show file tree
Hide file tree
Showing 3 changed files with 40 additions and 28 deletions.
17 changes: 17 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/defaults.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# CAN
CAN_P1_DRIVER 1 # Enables the use of CAN

# Onboard OSD
OSD_TYPE 5 # MSP
OSD_CELL_COUNT 0 # auto based on voltage at start

# Serial ports
SERIAL1_PROTOCOL 2 # Mavlink
SERIAL2_PROTOCOL 42 # DisplayPort
SERIAL3_PROTOCOL 5 # GPS
SERIAL4_PROTOCOL 0 # TODO: DJI HDL?
SERIAL5_PROTOCOL 16 # ESC telemetry
SERIAL6_PROTOCOL 23 # RCIN
SERIAL7_PROTOCOL 22 # SLCAN


16 changes: 6 additions & 10 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -1,16 +1,15 @@
# processed by chibios_hwdef.py
# Processed by chibios_hwdef.py

include common.inc

# bootloader is installed at zero offset
# Bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0

# the location where the bootloader will put the firmware
# Location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 128

env OPTIMIZE -Os

# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3

# CS pins
Expand All @@ -19,17 +18,13 @@ PI9 IMU1_CS CS
# SPI6 - external
PI10 EXT1_CS CS

# telem1
# Telem1 - Telem
PE8 UART7_TX UART7
PF6 UART7_RX UART7
PF8 UART7_RTS UART7
PE10 UART7_CTS UART7

# telem2
PC12 UART5_TX UART5
PD2 UART5_RX UART5

# armed indication
# Armed indication
PE6 nARMED OUTPUT HIGH

# 12V peripheral enable
Expand All @@ -40,5 +35,6 @@ PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red
PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue
define HAL_LED_ON 0

# No param flash storage for bootloader
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
35 changes: 17 additions & 18 deletions libraries/AP_HAL_ChibiOS/hwdef/ARK_FPV/hwdef.dat
Original file line number Diff line number Diff line change
@@ -1,32 +1,31 @@
# processed by chibios_hwdef.py
# Processed by chibios_hwdef.py

include common.inc

# ChibiOS system timer
STM32_ST_USE_TIMER 2


# bootloader takes first sector
# Bootloader takes first sector
FLASH_RESERVE_START_KB 128

# use last 2 pages for flash storage
# Use last 2 pages for flash storage
# H743 has 16 pages of 128k each
define HAL_STORAGE_SIZE 32768
STORAGE_FLASH_PAGE 14

# to be compatible with the px4 bootloader we need
# To be compatible with the px4 bootloader we need
# to use a different RAM_MAP
env USE_ALT_RAM_MAP 1

env OPTIMIZE -O2

SERIAL_ORDER OTG1 UART7 UART5 USART1 USART2 UART4 USART6 OTG2

# debug console
# Debug console
STDOUT_SERIAL SD3
STDOUT_BAUDRATE 57600

# default to all pins low to avoid ESD issues
# Default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN

# Telem1 - Telem
Expand Down Expand Up @@ -58,8 +57,7 @@ PC7 USART6_RX USART6
# ADCs
PA0 SCALED1_V3V3 ADC1 SCALE(2)
PB1 VDD_5V_SENS ADC1 SCALE(2)

# TODO: 12V
# TODO: 12V monitor
# PA4 SCALED2_V3V3 ADC1 SCALE(2)

PB0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
Expand All @@ -85,14 +83,14 @@ PG9 SPI1_MISO SPI1
PI9 IMU1_CS CS
PF2 IMU1_DRDY INPUT

# SPI6 - external
# SPI6 - external (SPI OSD or IMU)
PB3 SPI6_SCK SPI6
PA6 SPI6_MISO SPI6
PG14 SPI6_MOSI SPI6
PI10 EXT1_CS CS
PD11 DRDY_ADIS16507 INPUT GPIO(93)

# use GPIO(93) for data ready on ADIS16507
# GPIO(93) for data ready on ADIS16507
# define ADIS_DRDY_PIN 93

# Motors
Expand Down Expand Up @@ -139,10 +137,10 @@ define HAL_IMUHEAT_I_DEFAULT 0.07
# TODO: should we use this?
# define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5

# armed indication
# Armed indication
PE6 nARMED OUTPUT HIGH

# power enable pins
# Power enable pins
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH

Expand All @@ -151,7 +149,7 @@ PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH
# bootloader hold
PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH

# power sensing
# Power sensing
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
PG1 VDD_BRICK_nVALID INPUT PULLUP
Expand Down Expand Up @@ -196,17 +194,18 @@ IMU Invensensev3 SPI:iim42653 ROTATION_YAW_270

define HAL_DEFAULT_INS_FAST_SAMPLE 1

# Prioritze SD logging and IMU
DMA_PRIORITY SDMMC* SPI*

# Bidir DShot timers cannot share DMA
DMA_NOSHARE SPI* TIM5* TIM8*

# enable FAT filesystem support (needs a microSD defined via SDMMC)
# Enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1


# bootloader embedding / bootloader flashing not available
# Bootloader embedding / bootloader flashing not available
define AP_BOOTLOADER_FLASHING_ENABLED 0

# setup for OSD
# Setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 5 # MSP Displayport

0 comments on commit 5df3d64

Please sign in to comment.