# hw definition file for processing by chibios_pins.py # new F412 layout MCU STM32F4xx STM32F412Rx # board ID for firmware load APJ_BOARD_ID 9 # crystal frequency OSCILLATOR_HZ 24000000 STM32_HSE_ENABLED FALSE STM32_PLLM_VALUE 16 STM32_PLLN_VALUE 384 STM32_PLLP_VALUE 4 STM32_PLLQ_VALUE 8 STM32_PLLSRC STM32_PLLSRC_HSI STM32_PREE1 STM32_PREE1_DIV2 STM32_PREE2 STM32_PREE2_DIV1 STM32_PWM_USE_TIM3 TRUE # board voltage STM32_VDD 330U RAM_SIZE_KB 256 # flash size FLASH_SIZE_KB 1024 # serial port for stdout STDOUT_SERIAL SD1 STDOUT_BAUDRATE 115200 # order of I2C buses I2C_ORDER I2C2 I2C1 # we need I2C clock at 400kHz for IMU define HAL_I2C_MAX_CLOCK 400000 # run I2C bus thread at high priority for IMU define APM_I2C_PRIORITY 181 # order of UARTs UART_ORDER USART1 USART6 USART2 PC0 MGND ADC1 PC1 PWM4_SENSE ADC1 PC2 PWM2_SENSE ADC1 PC3 PWM1_SENSE ADC1 PA0 PWM3_SENSE ADC1 # USART2 is for sonix PA2 USART2_TX USART2 PA3 USART2_RX USART2 # SPI1 is radio PA4 RADIO_CS CS PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 PC4 RADIO_CE OUTPUT PC5 RADIO_PA_CTL OUTPUT PB0 RADIO_IRQ INPUT GPIO(100) PB1 BATT_MON ADC1 SCALE(11) PB2 BOOT1 INPUT PB10 I2C2_SCL I2C2 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD PB9 I2C1_SDA I2C1 PB8 I2C1_SCL I2C1 PB7 LEDF OUTPUT HIGH GPIO(0) PB6 LEDR OUTPUT HIGH GPIO(1) PB5 TIM3_CH2 TIM3 PWM(2) # marked CN15 front-right PB3 I2C2_SDA I2C2 PD2 OF_MOTION INPUT PB4 OF_RESET OUTPUT HIGH # USART6 is for GPS PA11 USART6_TX USART6 PC7 USART6_RX USART6 # USART1 is for debug console PA10 USART1_RX USART1 PA9 USART1_TX USART1 PC9 TIM3_CH4 TIM3 PWM(4) # marked CN17, rear-right PC8 TIM3_CH3 TIM3 PWM(3) # marked CN13, rear-left PC6 TIM3_CH1 TIM3 PWM(1) # marked CN3, front-left # SPI2 is optical flow PB15 SPI2_MOSI SPI2 PB14 SPI2_MISO SPI2 PB13 SPI2_SCK SPI2 PB12 FLOW_CS CS # SPI Device table SPIDEV cypress SPI1 DEVID1 RADIO_CS MODE0 2*MHZ 2*MHZ SPIDEV cc2500 SPI1 DEVID1 RADIO_CS MODE0 4*MHZ 4*MHZ SPIDEV pixartflow SPI2 DEVID2 FLOW_CS MODE3 2*MHZ 2*MHZ # reserve 16k for bootloader and 32k for storage FLASH_RESERVE_START_KB 48 define HAL_CHIBIOS_ARCH_F412 1 define HAL_INS_DEFAULT HAL_INS_MPU60XX_I2C define HAL_INS_DEFAULT_ROTATION ROTATION_NONE define HAL_INS_MPU60x0_I2C_BUS 1 define HAL_INS_MPU60x0_I2C_ADDR 0x68 # radio IRQ is on GPIO(100) define HAL_GPIO_RADIO_IRQ 100 define HAL_RCINPUT_WITH_AP_RADIO 1 define STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 16384 # setup defines for ArduCopter config define TOY_MODE_ENABLED ENABLED define ARMING_DELAY_SEC 0 define LAND_START_ALT 700 define LAND_DETECTOR_ACCEL_MAX 2.0f define ALLOW_ARM_NO_COMPASS define CHIBIOS_ADC_MAVLINK_DEBUG 1 define HAL_COMPASS_DEFAULT HAL_COMPASS_BMM150_I2C define HAL_COMPASS_BMM150_I2C_BUS 0 define HAL_COMPASS_BMM150_I2C_ADDR 0x10 define HAL_BARO_DEFAULT HAL_BARO_20789_I2C_I2C define HAL_BARO_20789_I2C_BUS 1 define HAL_BARO_20789_I2C_ADDR_PRESS 0x63 define HAL_BARO_20789_I2C_ADDR_ICM 0x68 # unstick 20789 on I2C on boot define HAL_I2C_CLEAR_BUS env DEFINES CONFIG_HAL_BOARD_SUBTYPE='HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412' env DEFAULT_PARAMETERS 'Tools/Frame_params/SkyViper-F412/defaults.parm' # the web UI uses an abin file for firmware uploads env BUILD_ABIN True