Skip to content

Commit

Permalink
AP_HAL_ChibiOS/hwdef: Add hwdef for Sierra True series periphs
Browse files Browse the repository at this point in the history
  • Loading branch information
MallikarjunSE authored and tridge committed Aug 24, 2023
1 parent 6ffbc21 commit 00879e9
Show file tree
Hide file tree
Showing 7 changed files with 501 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# setup for Neopixel
OUT1_FUNCTION 120
NTF_LED_TYPES 455
NTF_LED_LEN 2
60 changes: 60 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# HW definition file for Sierra-TrueNav Pro

# MCU class and specific type
MCU STM32L431 STM32L431xx

# crystal frequency
OSCILLATOR_HZ 16000000

# board ID for firmware load
APJ_BOARD_ID 1091

# setup build for a peripheral firmware
env AP_PERIPH 1

# Flash info
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 36
FLASH_SIZE_KB 256

# reserve some space for params
APP_START_OFFSET_KB 4

# a fault LED
PA1 LED_BOOTLOADER OUTPUT LOW # amber
define HAL_LED_ON 1

# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH

CAN_ORDER 1

# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600

# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000

define HAL_USE_SERIAL FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define DMA_RESERVE_SIZE 0

MAIN_STACK 0x800
PROCESS_STACK 0x800

define HAL_DISABLE_LOOP_DELAY

# Add CS pins to ensure they are high in bootloader
PB12 RM3100_CS CS
PA8 BARO_CS CS

# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro"
118 changes: 118 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
# HW definition file for Sierra-TrueNav Pro

# MCU class and specific type
MCU STM32L431 STM32L431xx

# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
FLASH_RESERVE_START_KB 40
FLASH_SIZE_KB 256

# store parameters in pages 18 and 19
STORAGE_FLASH_PAGE 18
define HAL_STORAGE_SIZE 800

# ChibiOS system timer
STM32_ST_USE_TIMER 15
define CH_CFG_ST_RESOLUTION 16

# board ID for firmware load
APJ_BOARD_ID 1091

# crystal frequency
OSCILLATOR_HZ 16000000

env AP_PERIPH 1

define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 512
define PORT_INT_REQUIRED_STACK 64

define DMA_RESERVE_SIZE 0

# MAIN_STACK is stack for ISR handlers
MAIN_STACK 0x300

# PROCESS_STACK controls stack for main thread
PROCESS_STACK 0xA00

# save memory
define HAL_DISABLE_LOOP_DELAY
define HAL_GCS_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_NO_LOGGING
define HAL_USE_ADC FALSE
define HAL_NO_RCIN_THREAD

# we setup a small defaults.parm
define AP_PARAM_MAX_EMBEDDED_PARAM 256

# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# --------------------- SPI1 RM3100+DPS310 -----------------------
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PB12 RM3100_CS CS
PA8 BARO_CS CS

# Baro probe
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
BARO DPS310 SPI:dps310

# Mag probe
SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180
define AP_RM3100_REVERSAL_MASK 7

# ---------------------- CAN bus -------------------------
CAN_ORDER 1

PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW

define HAL_CAN_POOL_SIZE 12000

# ---------------------- UARTs ---------------------------
SERIAL_ORDER USART1

# USART1 for GPS
PA9 USART1_TX USART1 SPEED_HIGH
PA10 USART1_RX USART1 SPEED_HIGH

# allow for reboot command for faster development
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0

# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True

# enable GPS and compass
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY

# disable dual GPS and GPS blending to save flash space
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_PERIPH_GPS_PORT_DEFAULT 0

# minimal GPS drivers to reduce flash usage
include ../include/minimal_GPS.inc

# GPS PPS
PA15 GPS_PPS_IN INPUT

# PWM, WS2812 LED
PB10 TIM2_CH3 TIM2 PWM(1) GPIO(50)

define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro"

# Enable GPS LDO
PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH
57 changes: 57 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
# HW definition file for Sierra-TrueNorth

# MCU class and specific type
MCU STM32L431 STM32L431xx

# crystal frequency
OSCILLATOR_HZ 16000000

# board ID for firmware load
APJ_BOARD_ID 1093

# setup build for a peripheral firmware
env AP_PERIPH 1

# Flash info
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 36
FLASH_SIZE_KB 256

# reserve some space for params
APP_START_OFFSET_KB 4

# a fault LED
PB14 LED_BOOTLOADER OUTPUT LOW # amber
define HAL_LED_ON 1

# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PA10 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB12 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH

CAN_ORDER 1

# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600

# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000

define HAL_USE_SERIAL FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define DMA_RESERVE_SIZE 0

MAIN_STACK 0x800
PROCESS_STACK 0x800

define HAL_DISABLE_LOOP_DELAY

# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNorth"
PA4 RM3100_CS CS
97 changes: 97 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
# HW definition file for Sierra-TrueNorth

# MCU class and specific type
MCU STM32L431 STM32L431xx

# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
FLASH_RESERVE_START_KB 40
FLASH_SIZE_KB 256

# store parameters in pages 18 and 19
STORAGE_FLASH_PAGE 18
define HAL_STORAGE_SIZE 800

# ChibiOS system timer
STM32_ST_USE_TIMER 15
define CH_CFG_ST_RESOLUTION 16

# board ID for firmware load
APJ_BOARD_ID 1093

# crystal frequency
OSCILLATOR_HZ 16000000

env AP_PERIPH 1

define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 512
define PORT_INT_REQUIRED_STACK 64

define DMA_RESERVE_SIZE 0

# MAIN_STACK is stack for ISR handlers
MAIN_STACK 0x300

# PROCESS_STACK controls stack for main thread
PROCESS_STACK 0xA00

# save memory
define HAL_DISABLE_LOOP_DELAY
define HAL_GCS_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_NO_LOGGING
define HAL_USE_ADC FALSE
define HAL_NO_RCIN_THREAD

# we setup a small defaults.parm
define AP_PARAM_MAX_EMBEDDED_PARAM 256

# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# ---------------------- CAN bus -------------------------
CAN_ORDER 1

PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PA10 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB12 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH

define HAL_CAN_POOL_SIZE 6000

# allow for reboot command for faster development
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0

# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True

# enable compass and airspeed
define HAL_PERIPH_ENABLE_MAG
define HAL_COMPASS_MAX_SENSORS 1

# PWM, WS2812 LED
PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50)
PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51)

define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNorth"

# SPI1 bus for RM3100
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA4 RM3100_CS CS

SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180

# LEDs
PB14 LED OUTPUT LOW GPIO(1)

# ---------------------- UARTs ---------------------------
SERIAL_ORDER USART1

# USART1
PA9 USART1_TX USART1 SPEED_HIGH
PB7 USART1_RX USART1 SPEED_HIGH
56 changes: 56 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# HW definition file for Sierra-TrueSpeed

# MCU class and specific type
MCU STM32L431 STM32L431xx

# crystal frequency
OSCILLATOR_HZ 16000000

# board ID for firmware load
APJ_BOARD_ID 1094

# setup build for a peripheral firmware
env AP_PERIPH 1

# Flash info
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 36
FLASH_SIZE_KB 256

# reserve some space for params
APP_START_OFFSET_KB 4

# a fault LED
PA1 LED_BOOTLOADER OUTPUT LOW # amber
define HAL_LED_ON 1

# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH

CAN_ORDER 1

# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600

# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000

define HAL_USE_SERIAL FALSE
define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define DMA_RESERVE_SIZE 0

MAIN_STACK 0x800
PROCESS_STACK 0x800

define HAL_DISABLE_LOOP_DELAY

# debugger support
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

define CAN_APP_NODE_NAME "in.sierraaerospace.TrueSpeed"
Loading

0 comments on commit 00879e9

Please sign in to comment.