Skip to content

Commit

Permalink
AP_HAL_ChibiOS: Add Sierra-F9P support
Browse files Browse the repository at this point in the history
  • Loading branch information
MallikarjunSE authored and tridge committed Mar 9, 2022
1 parent cdd63a2 commit 228796d
Show file tree
Hide file tree
Showing 2 changed files with 242 additions and 0 deletions.
80 changes: 80 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
# hw definition file for processing by chibios_pins.py

# Sierra-F9P bootloader

# MCU class and specific type
MCU STM32F4xx STM32F412Rx

FLASH_RESERVE_START_KB 0
# two sectors for bootloader, two for storage
FLASH_BOOTLOADER_LOAD_KB 64

# board ID for firmware load
APJ_BOARD_ID 1034

# setup build for a peripheral firmware
env AP_PERIPH 1

# crystal frequency
OSCILLATOR_HZ 16000000

define CH_CFG_ST_FREQUENCY 1000000

# Available Flash
FLASH_SIZE_KB 1024

define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600

# order of UARTs
SERIAL_ORDER

# USART1
PA9 USART1_TX USART1
PA10 USART1_RX USART1

# USART2
PA2 USART2_TX USART2
PA3 USART2_RX USART2

# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_SERIAL TRUE

define STM32_SERIAL_USE_USART1 TRUE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 FALSE

define HAL_NO_GPIO_IRQ
define HAL_USE_EMPTY_IO TRUE

define DMA_RESERVE_SIZE 0

define HAL_DISABLE_LOOP_DELAY

# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE

define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P"

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

# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000

# Add CS pins to ensure they are high in bootloader
#PC6 ICM_CS CS
PC12 BARO_CS CS

#Sensors Enable & ESP Enable
PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH
PC2 ESP_PWR_EN OUTPUT LOW
162 changes: 162 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,162 @@
# hw definition file for processing by chibios_pins.py

# Sierra-F9P Firmware

# MCU class and specific type
MCU STM32F4xx STM32F412Rx

# bootloader starts firmware at 64k
FLASH_RESERVE_START_KB 64

# store parameters in pages 2 and 3
STORAGE_FLASH_PAGE 2
define HAL_STORAGE_SIZE 8192

# board ID for firmware load
APJ_BOARD_ID 1034

# setup build for a peripheral firmware
env AP_PERIPH 1
#env AP_PERIPH_HEAVY 1

STM32_ST_USE_TIMER 5

# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true

# crystal frequency
OSCILLATOR_HZ 16000000

define CH_CFG_ST_FREQUENCY 1000000

# Available Flash
FLASH_SIZE_KB 1024

STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600

# order of UARTs
SERIAL_ORDER USART1 EMPTY EMPTY USART2

# USART1 for debug
PA9 USART1_TX USART1 NODMA
PA10 USART1_RX USART1 NODMA
define HAL_SERIAL0_BAUD_DEFAULT 57600

# USART2 for GPS
PA2 USART2_TX USART2 SPEED_HIGH
PA3 USART2_RX USART2 SPEED_HIGH

# SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# only one I2C bus in normal config
PB7 I2C1_SDA I2C1
PB6 I2C1_SCL I2C1

define HAL_USE_I2C TRUE
define STM32_I2C_USE_I2C1 TRUE
define HAL_I2C_CLEAR_ON_TIMEOUT 0
define HAL_I2C_INTERNAL_MASK 0

# only one I2C bus
I2C_ORDER I2C1

# only one SPI bus in normal config
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI CS
#PC6 ICM_CS CS
PC12 BARO_CS CS

# SPI devices
# ToDo SPI devices
#SPIDEV icm20948 SPI1 DEVID1 MPU_CS MODE3 4*MHZ 8*MHZ
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ

# Compass
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90

# Baro
BARO DPS310 SPI:dps310

# PWM output for buzzer
PB5 TIM3_CH2 TIM3 GPIO(77) LOW ALARM

# WS2812 LEDs
PA15 TIM2_CH1 TIM2 PWM(1)

define HAL_USE_ADC TRUE
define STM32_ADC_USE_ADC1 TRUE
#define HAL_DISABLE_ADC_DRIVER TRUE
PA0 VSENSE ADC1 SCALE(2)

define HAL_NO_GPIO_IRQ

# avoid RCIN thread to save memory
define HAL_NO_RCIN_THREAD
define HAL_USE_RTC TRUE
define DISABLE_SERIAL_ESC_COMM TRUE
define DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
define PERIPH_FW TRUE

# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW

define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P"

define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0
define HAL_BUILD_AP_PERIPH
define HAL_DEVICE_THREAD_STACK 768

# we setup a small defaults.parm
define AP_PARAM_MAX_EMBEDDED_PARAM 256

# 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

# GPS+MAG+BARO+Buzzer+NeoPixels
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
define CONFIGURE_PPS_PIN TRUE
#define HAL_INS_ENABLED 1
define GPS_MOVING_BASELINE 1

# Logging
define HAL_LOGGING_ENABLED 1
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"

# SD Card pins
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
PC11 SDIO_D3 SDIO
PB15 SDIO_CK SDIO
PD2 SDIO_CMD SDIO

# use the app descriptor needed by MissionPlanner for CAN upload
env APP_DESCRIPTOR MissionPlanner

# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256

# allow for reboot command for faster development
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0

#Sensors Enable & ESP Enable
PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH
PC2 ESP_PWR_EN OUTPUT LOW

0 comments on commit 228796d

Please sign in to comment.