hwdef: Update hwdef to have only mag and airspeed

This commit is contained in:
MallikarjunSE 2022-01-26 19:06:29 +05:30 committed by Andrew Tridgell
parent a897fbc6db
commit a4b5bf1f4f
2 changed files with 38 additions and 87 deletions

View File

@ -1,5 +1,7 @@
# hw definition file for processing by chibios_pins.py
# Sierra RM3100 & Airspeed common hwdef
# MCU class and specific type
MCU STM32L431 STM32L431xx
@ -18,44 +20,33 @@ env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 16000000
# assume 256k flash part
# Flash available
FLASH_SIZE_KB 256
# a fault LED
PA15 LED_BOOTLOADER OUTPUT LOW # amber
define HAL_LED_ON 1
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# order of UARTs
SERIAL_ORDER USART1 USART2
# a fault LED
PB0 LED_BOOTLOADER OUTPUT LOW # blue
define HAL_LED_ON 1
PB14 LED_RED OUTPUT LOW GPIO(1)
SERIAL_ORDER USART1
# USART1
PA9 USART1_TX USART1 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
# USART2
PA2 USART2_TX USART2 SPEED_HIGH NODMA
PA3 USART2_RX USART2 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define STM32_SERIAL_USE_USART2 TRUE
define SERIAL_BUFFERS_SIZE 32
define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define DMA_RESERVE_SIZE 0
MAIN_STACK 0x800
PROCESS_STACK 0x800
@ -64,8 +55,6 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
CAN_ORDER 1
# debugger support
@ -78,16 +67,7 @@ define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
# Enable the GPS voltage pin
PC13 GPS_EN OUTPUT HIGH
# Enable the sensor voltage pin
PC12 SENSOR_EN OUTPUT HIGH
# Add CS pins to ensure they are high in bootloader
#PC6 MPU_CS CS
PA8 BARO_CS CS
PB12 MAG_CS CS

View File

@ -1,4 +1,6 @@
g# hw definition file for processing by chibios_pins.py
# hw definition file for processing by chibios_pins.py
# Sierra RM3100 & Airspeed common hwdef
# MCU class and specific type
MCU STM32L431 STM32L431xx
@ -20,56 +22,47 @@ APJ_BOARD_ID 1050
# setup build for a peripheral firmware
env AP_PERIPH 1
# enable watchdog
# crystal frequency
OSCILLATOR_HZ 16000000
# assume the 256k flash part
# Flash available
FLASH_SIZE_KB 256
# order of UARTs
SERIAL_ORDER USART1 USART2
define HAL_CAN_POOL_SIZE 6000
#STDOUT_SERIAL SD1
#STDOUT_BAUDRATE 57600
# USART1 Debug
PA9 USART1_TX USART1 SPEED_HIGH
PA10 USART1_RX USART1 SPEED_HIGH
# USART2 M9N
PA2 USART2_TX USART2 SPEED_HIGH
PA3 USART2_RX USART2 SPEED_HIGH
# LEDs
PB0 LED OUTPUT LOW GPIO(1)
PA15 LED OUTPUT LOW GPIO(1)
# a fault LED
# PB14 LED_FAULT OUTPUT LOW # red
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# SPI1 bus for Baro
# order of UARTs
SERIAL_ORDER USART1
# USART1
PA9 USART1_TX USART1 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define SERIAL_BUFFERS_SIZE 32
# SPI1 bus for RM3100
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA8 BARO_CS CS
PB12 MAG_CS CS
SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
BARO DPS280 SPI:dps310
# compass
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
#SPIDEV Invensensev2 SPI2 DEVID2 IMU_CS MODE3 2*MHZ 8*MHZ
# QMC5883L
# MS4525DO Airspeed
PB6 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
I2C_ORDER I2C1
# compass
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90
# allow for reboot command for faster development
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
@ -78,11 +71,8 @@ PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 512
define DMA_RESERVE_SIZE 2048
# stack for fast interrupts
define PORT_INT_REQUIRED_STACK 64
@ -97,40 +87,21 @@ define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
CAN_ORDER 1
define HAL_USE_ADC TRUE
define STM32_ADC_USE_ADC1 TRUE
PA4 VSENSE ADC1 SCALE(2)
PA0 VSENSE ADC1 SCALE(2)
define HAL_GCS_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_NO_LOGGING
define HAL_MINIMIZE_FEATURES 0
define AP_PARAM_MAX_EMBEDDED_PARAM 512
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_GPS_PORT_DEFAULT 1
define HAL_PERIPH_ENABLE_MAG
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED
#BARO MS56XX SPI:ms5611
#BARO BMP388 I2C:0:0x76
# define HAL_SPI_CHECK_CLOCK_FREQ
# WS2812 LED
PA15 TIM2_CH1 TIM2 PWM(1)
PB11 TIM2_CH4 TIM2 PWM(2)
define AIRSPEED_MAX_SENSORS 1
define HAL_AIRSPEED_TYPE_DEFAULT 1