123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176 |
- # hw definition file for processing by chibios_hwdef.py
- # for VRCOREv10 hardware
- define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_VRCORE_V10
- # MCU class and specific type
- MCU STM32F4xx STM32F407xx
- # board ID for firmware load
- APJ_BOARD_ID 1910
- # crystal frequency
- OSCILLATOR_HZ 8000000
- STM32_PLLM_VALUE 8
- # flash size
- FLASH_SIZE_KB 1024
- # board voltage
- STM32_VDD 330U
- # USB setup
- USB_VENDOR 0x27AC
- USB_PRODUCT 0x1910
- USB_STRING_MANUFACTURER "Laser Navigation"
- USB_STRING_SERIAL "%SERIAL%"
- # ChibiOS system timer
- STM32_ST_USE_TIMER 5
- # only one I2C bus
- I2C_ORDER I2C2 I2C1
- # order of UARTs (and USB)
- UART_ORDER OTG1 USART1 USART3 USART2
- STDOUT_SERIAL SD3
- STDOUT_BAUDRATE 57600
- PA0 BUZZER OUTPUT LOW GPIO(32)
- PA1 TIM2_CH2 TIM2 PWM(1) GPIO(50)
- PA2 TIM2_CH3 TIM2 PWM(2) GPIO(51)
- PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
- PA4 SDCARD_CS CS
- PA5 SPI1_SCK SPI1
- PA6 SPI1_MISO SPI1
- PA7 SPI1_MOSI SPI1
- #PA8
- PA9 VBUS INPUT
- #P10
- PA11 OTG_FS_DM OTG1
- PA12 OTG_FS_DP OTG1
- PA13 JTMS-SWDIO SWD
- PA14 JTCK-SWCLK SWD
- #PA15
- PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)
- PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
- #PB2
- PB3 LED_EXT3 OUTPUT GPIO(30)
- PB4 LED_EXT4 OUTPUT GPIO(31)
- PB5 TIM3_CH2 TIM3 PWM(4) GPIO(53)
- PB6 USART1_TX USART1
- PB7 USART1_RX USART1
- PB8 I2C1_SCL I2C1
- PB9 I2C1_SDA I2C1
- PB10 I2C2_SCL I2C2
- PB11 I2C2_SDA I2C2
- #PB12
- PB13 SPI2_SCK SPI2
- PB14 SPI2_MISO SPI2
- PB15 SPI2_MOSI SPI2
- PC0 BATT_VOLTAGE_SENS ADC1
- PC1 BATT_CURRENT_SENS ADC1
- #PC2
- #PC3
- #PC4
- PC5 LED_GREEN OUTPUT GPIO(25)
- #PC6
- PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
- PC8 RELAY_1 OUTPUT LOW GPIO(33)
- PC9 RELAY_2 OUTPUT LOW GPIO(34)
- PC10 SPI3_SCK SPI3
- PC11 SPI3_MISO SPI3
- PC12 SPI3_MOSI SPI3
- #PC13
- #PC14
- #PC15
- #PD0
- #PD1
- #PD2
- #PD3
- #PD4
- PD5 USART2_TX USART2
- PD6 USART2_RX USART2
- PD7 SBUS_INV OUTPUT
- PD8 USART3_TX USART3
- PD9 USART3_RX USART3
- #PD10
- #PD11
- PD12 TIM4_CH1 TIM4 PWM(8) GPIO(57)
- PD13 TIM4_CH2 TIM4 PWM(7) GPIO(56)
- PD15 LED_RED OUTPUT GPIO(27)
- PD14 LED_BLUE OUTPUT GPIO(26)
- PE0 BARO_CS CS
- #PE1
- PE2 LED_EXT1 OUTPUT GPIO(29)
- PE3 LED_EXT2 OUTPUT GPIO(28)
- PE4 RELAY_3 OUTPUT LOW GPIO(35)
- #PE5 TIM9_CH1 TIM9 PWM(13) GPIO(62)
- #PE6 TIM9_CH2 TIM9 PWM(14) GPIO(63)
- #PE7
- #PE8
- PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58)
- PE10 MPU_CS CS
- PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59)
- #PE12
- PE13 TIM1_CH3 TIM1 PWM(11) GPIO(60)
- PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61)
- PE15 FRAM_CS CS
- # 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 mpu9250 SPI2 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ
- SPIDEV ramtron SPI3 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
- SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
- define HAL_CHIBIOS_ARCH_COREV10 1
- define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
- define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
- define HAL_STORAGE_SIZE 16384
- define STORAGE_FLASH_PAGE 22
- # enable RAMTROM parameter storage
- define HAL_WITH_RAMTRON 1
- # enable FAT filesystem
- define HAL_OS_FATFS_IO 1
- define HAL_GPIO_LED_ON 0
- define HAL_GPIO_LED_OFF 1
- define HAL_GPIO_A_LED_PIN 25
- define HAL_GPIO_B_LED_PIN 26
- define HAL_GPIO_C_LED_PIN 27
- define EXTERNAL_LED_GPS 28
- define EXTERNAL_LED_ARMED 29
- define EXTERNAL_LED_MOTOR1 30
- define EXTERNAL_LED_MOTOR2 31
- define RELAY1_PIN_DEFAULT 33
- define RELAY2_PIN_DEFAULT 34
- define RELAY3_PIN_DEFAULT 35
- define HAL_BUZZER_PIN 32
- define HAL_BUZZER_ON 1
- define HAL_BUZZER_OFF 0
- # battery setup
- define HAL_BATT_VOLT_PIN 10
- define HAL_BATT_CURR_PIN 11
- define HAL_BATT_VOLT_SCALE 10.1
- define HAL_BATT_CURR_SCALE 17.0
- define STM32_PWM_USE_ADVANCED TRUE
- # 12 PWM available by default
- define BOARD_PWM_COUNT_DEFAULT 14
|