123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216 |
- # hw definition file for processing by chibios_hwdef.py
- # for MindPX-v2 hardware
- # MCU class and specific type
- MCU STM32F4xx STM32F427xx
- define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
- # board ID for firmware load
- APJ_BOARD_ID 88
- # crystal frequency
- OSCILLATOR_HZ 8000000
- STM32_PLLM_VALUE 8
- STM32_ST_USE_TIMER 5
- # board voltage
- STM32_VDD 330U
- # flash size
- FLASH_SIZE_KB 2048
- # space to reserve for bootloader and storage at start of flash
- FLASH_RESERVE_START_KB 16
- # space to reserve for storage at end of flash
- FLASH_RESERVE_END_KB 0
- # serial port for stdout disabled, uses USB instead
- # STDOUT_SERIAL SD7
- # STDOUT_BAUDRATE 57600
- # order of I2C buses
- I2C_ORDER I2C1 I2C2
- # order of UARTs (and USB)
- UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
- # UART4 is GPS
- PA0 UART4_TX UART4
- PA1 UART4_RX UART4
- PA4 VDD_5V_SENS ADC1 SCALE(2)
- # SPI1 is fram bus
- PA5 SPI1_SCK SPI1
- PA6 SPI1_MISO SPI1
- # Timers 1-4 are used for (servo) PWM outputs and 5/6 are used for clocks
- # Use Timer 14 for tone generation
- PA7 TIM14_CH1 TIM14 GPIO(32) ALARM
- PA8 RUN_LED OUTPUT GPIO(0)
- PA9 VBUS INPUT
- PA10 SBUS_INV OUTPUT
- PA11 OTG_FS_DM OTG1
- PA12 OTG_FS_DP OTG1
- PA13 JTMS-SWDIO SWD
- PA14 JTCK-SWCLK SWD
- # PWM outputs
- PE9 TIM1_CH1 TIM1 PWM(1)
- PE11 TIM1_CH2 TIM1 PWM(2)
- PE13 TIM1_CH3 TIM1 PWM(3)
- PE14 TIM1_CH4 TIM1 PWM(4)
- PD12 TIM4_CH1 TIM4 PWM(5)
- PD13 TIM4_CH2 TIM4 PWM(6)
- PD14 TIM4_CH3 TIM4 PWM(7)
- PD15 TIM4_CH4 TIM4 PWM(8)
- PB4 TIM3_CH1 TIM3 PWM(9) GPIO(50)
- PC7 TIM3_CH2 TIM3 PWM(10) GPIO(51)
- PB0 TIM3_CH3 TIM3 PWM(11) GPIO(52)
- PB1 TIM3_CH4 TIM3 PWM(12) GPIO(53)
- PA15 TIM2_CH1 TIM2 PWM(13) GPIO(54)
- PB3 TIM2_CH2 TIM2 PWM(14) GPIO(55)
- PA2 TIM2_CH3 TIM2 PWM(15)
- PA3 TIM2_CH4 TIM2 PWM(16)
- PB2 GYRO_CS CS
- PB5 SPI1_MOSI SPI1
- # USART1 is SBUS
- PB6 USART1_TX USART1
- PB7 USART1_RX USART1
- # I2C1 is mag I2C
- PB8 I2C1_SCL I2C1
- PB9 I2C1_SDA I2C1
- # I2C2 is FMU I2C
- PB10 I2C2_SCL I2C2
- PB11 I2C2_SDA I2C2
- # SPI2 is external SPI (radio NRF)
- PB13 SPI2_SCK SPI2
- PB14 SPI2_MISO SPI2
- PB15 SPI2_MOSI SPI2
- PC0 BAT_CURR_SENS ADC1
- PC1 FMU_GPIO3 INPUT # RSSI
- PC2 BAT_VOLT_SENS ADC1
- PC3 FMU_ADC1 ADC1
- PC4 FMU_ADC2 ADC1
- PC5 FMU_ADC3 ADC1
- PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC
- PC8 SDIO_D0 SDIO
- PC9 SDIO_D1 SDIO
- PC10 SDIO_D2 SDIO
- PC11 SDIO_D3 SDIO
- PC12 SDIO_CK SDIO
- PC13 ACCEL_DRDY INPUT
- PC14 MAG_DRDY INPUT
- PC15 BARO_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 NRF_CSN INPUT
- # USART3 serial3 telem2
- PD8 USART3_TX USART3
- PD9 USART3_RX USART3
- PD10 NRF_INT INPUT
- PD11 ACCEL_MAG_CS CS
- # UART8 is FrSky
- PE0 UART8_RX UART8
- PE1 UART8_TX UART8
- # allow this uart to be inverted for transmit under user control
- # the polarity is the value to use on the GPIO to change the polarity
- # to the opposite of the default
- PB12 UART8_TXINV OUTPUT HIGH GPIO(78) POL(0)
- # SPI4 is M_SPI (main sensors)
- PE2 SPI4_SCK SPI4
- PE3 MPU_CS CS
- PE4 GYRO_DRDY INPUT
- PE5 SPI4_MISO SPI4
- PE6 SPI4_MOSI SPI4
- # UART7 is debug
- PE7 UART7_RX UART7
- PE8 UART7_TX UART7
- PE10 MPU_DRDY INPUT
- PE12 FRAM_CS CS
- PE15 NRF_CS CS
- # SPI device table
- SPIDEV ms5611 SPI4 DEVID1 BARO_CS MODE3 2*MHZ 2*MHZ
- SPIDEV mpu6500 SPI4 DEVID2 MPU_CS MODE3 500*KHZ 4*MHZ
- SPIDEV lsm9ds0_am SPI4 DEVID3 ACCEL_MAG_CS MODE3 11*MHZ 11*MHZ
- SPIDEV lsm9ds0_g SPI4 DEVID4 GYRO_CS MODE3 11*MHZ 11*MHZ
- SPIDEV ramtron SPI1 DEVID5 FRAM_CS MODE3 8*MHZ 8*MHZ
- SPIDEV radio SPI2 DEVID6 NRF_CS MODE3 2*MHZ 2*MHZ
- # two IMUs
- IMU Invensense SPI:mpu6500 ROTATION_NONE
- IMU LSM9DS0 SPI:lsm9ds0_g SPI:lsm9ds0_am ROTATION_YAW_90 ROTATION_YAW_90 ROTATION_YAW_90
- # one baro
- BARO MS56XX SPI:ms5611
- # two compasses
- COMPASS HMC5843 I2C:0:0x1e false ROTATION_YAW_90
- COMPASS LSM303D SPI:lsm9ds0_am ROTATION_PITCH_180_YAW_270
- define HAL_PROBE_EXTERNAL_I2C_COMPASSES
- define HAL_CHIBIOS_ARCH_MINDPXV2 1
- define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
- define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
- define HAL_STORAGE_SIZE 16384
- # enable RAMTROM parameter storage
- define HAL_WITH_RAMTRON 1
- # fallback to flash storage
- define STORAGE_FLASH_PAGE 22
- # allow to have have a dedicated safety switch pin
- define HAL_HAVE_SAFETY_SWITCH 1
- # enable FAT filesystem
- define HAL_OS_FATFS_IO 1
- # enable RTSCTS
- define AP_FEATURE_RTSCTS 1
- # battery setup
- define HAL_BATT_VOLT_PIN 12
- define HAL_BATT_CURR_PIN 10
- define HAL_BATT_VOLT_SCALE 10.1
- define HAL_BATT_CURR_SCALE 17.0
- # 12 PWM available by default
- define BOARD_PWM_COUNT_DEFAULT 12
|