ardupilot/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat

190 lines
4.8 KiB
Plaintext
Raw Normal View History

2018-01-10 06:33:37 -04:00
# hw definition file for processing by chibios_hwdef.py
# for FMUv3 hardware
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# board ID for firmware load
APJ_BOARD_ID 9
# crystal frequency
OSCILLATOR_HZ 24000000
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600
# USB setup
USB_VENDOR 0x0483 # ST
USB_PRODUCT 0x5740
USB_STRING_MANUFACTURER "ArduPilot"
USB_STRING_PRODUCT "%BOARD%"
USB_STRING_SERIAL "%SERIAL%"
2018-01-10 06:33:37 -04:00
# order of I2C buses
I2C_ORDER I2C2 I2C1
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART2 USART3 UART8
# UART for IOMCU
IOMCU_UART USART6
# UART4 serial GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
PA4 VDD_5V_SENS ADC1 SCALE(2)
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA8 VDD_5V_PERIPH_EN OUTPUT LOW
PA9 VBUS INPUT OPENDRAIN
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# PA15 ALARM
PB0 EXTERN_GPIO1 OUTPUT GPIO(1)
PB1 EXTERN_GPIO2 OUTPUT GPIO(2)
PB2 BOOT1 INPUT
PB3 FMU_SW0 INPUT
PB6 CAN2_TX CAN2
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
PB12 CAN2_RX CAN2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 VBUS_VALID INPUT
PC1 MAG_CS CS
PC2 MPU_CS CS
PC3 AUX_POWER ADC1 SCALE(1)
PC4 AUX_ADC2 ADC1 SCALE(1)
PC5 PRESSURE_SENS ADC1 SCALE(2)
# USART6 to IO
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
PC11 SDIO_D3 SDIO
PC12 SDIO_CK SDIO
PC13 GYRO_EXT_CS CS
PC14 BARO_EXT_CS CS
PC15 ACCEL_EXT_CS CS
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PD2 SDIO_CMD SDIO
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD7 BARO_CS CS
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
2018-01-20 01:56:56 -04:00
PD10 FRAM_CS CS SPEED_VERYLOW
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
PD15 MPU_DRDY INPUT
# UART8 serial4 GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
PE2 SPI4_SCK SPI4
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
PE4 MPU_EXT_CS CS
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# UART7 debug console
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
PE10 VDD_5V_HIPOWER_OC INPUT
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PE12 FMU_LED_AMBER OUTPUT GPIO(0)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE15 VDD_5V_PERIPH_OC INPUT
# SPI device table. The DEVID values are chosen to match the PX4 port
# of ArduPilot so users don't need to re-do their accel and compass calibrations
# when moving to ChibiOS
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE3 1*MHZ 8*MHZ
SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 4*MHZ
SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 4*MHZ
SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
SPIDEV lsm9ds0_g SPI1 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
SPIDEV lsm9ds0_am SPI1 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
SPIDEV lsm9ds0_ext_g SPI4 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
SPIDEV lsm9ds0_ext_am SPI4 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV external0m0 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ
SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ
SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ
SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ
# for SPI clock testing
#SPIDEV clock500 SPI4 DEVID5 MPU_EXT_CS MODE0 500*KHZ 500*KHZ # gives 329KHz
#SPIDEV clock1 SPI4 DEVID5 MPU_EXT_CS MODE0 1*MHZ 1*MHZ # gives 657kHz
#SPIDEV clock2 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ # gives 1.3MHz
#SPIDEV clock4 SPI4 DEVID5 MPU_EXT_CS MODE0 4*MHZ 4*MHZ # gives 2.6MHz
#SPIDEV clock8 SPI4 DEVID5 MPU_EXT_CS MODE0 8*MHZ 8*MHZ # gives 5.5MHz
#SPIDEV clock16 SPI4 DEVID5 MPU_EXT_CS MODE0 16*MHZ 16*MHZ # gives 10.6MHz
define HAL_CHIBIOS_ARCH_FMUV3 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define HAL_STORAGE_SIZE 16384
# fallback storage location is flash if no FRAM fitted
define STORAGE_FLASH_PAGE 22
# enable RAMTROM parameter storage
define HAL_WITH_RAMTRON 1
# pixhawk2 cube has an IMU header
define HAL_HAVE_IMU_HEATER 1
# enable FAT filesystem
define HAL_OS_FATFS_IO 1
# enable RTSCTS
define AP_FEATURE_RTSCTS 1
# enable SBUS_OUT on IOMCU
define AP_FEATURE_SBUS_OUT 1
# enable UAVCAN
define HAL_WITH_UAVCAN 1
# battery pins
define HAL_BATT_VOLT_PIN 2
define HAL_BATT_CURR_PIN 3
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0