# hw definition for Sierra-F405 # MCU class and specific type MCU STM32F4xx STM32F405xx # bootloader starts firmware at 64k FLASH_RESERVE_START_KB 64 FLASH_SIZE_KB 1024 # store parameters in pages 2 and 3 STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 15360 # board ID for firmware load APJ_BOARD_ID 1052 env AP_PERIPH 1 define STM32_ST_USE_TIMER 5 define CH_CFG_ST_RESOLUTION 32 # enable watchdog define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 define HAL_NO_GPIO_IRQ # avoid timer and RCIN threads to save memory define HAL_NO_RCIN_THREAD define HAL_USE_RTC FALSE define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 define HAL_DISABLE_LOOP_DELAY define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING define HAL_MINIMIZE_FEATURES 0 define DISABLE_SERIAL_ESC_COMM TRUE define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm define AP_PARAM_MAX_EMBEDDED_PARAM 256 # keep ROMFS uncompressed as we don't have enough RAM # to uncompress the bootloader at runtime env ROMFS_UNCOMPRESSED True # --------------------- SPI2 RM3100 + DPS310 -------------------- PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 PA8 BARO_CS CS PB12 MAG_CS CS # ---------------------- CAN bus ------------------------- PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 CAN_ORDER 1 # use DNA for node allocation define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405" # order of UARTs SERIAL_ORDER USART1 EMPTY EMPTY USART2 # USART1 for debug PA9 USART1_TX USART1 PA10 USART1_RX USART1 define HAL_SERIAL0_BAUD_DEFAULT 57600 # USART2 M9N PA2 USART2_TX USART2 SPEED_HIGH PA3 USART2_RX USART2 SPEED_HIGH # --------------------- CAM Trigger + Feedback ----------------------- PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) PB9 TIM4_CH4 TIM4 PWM(2) GPIO(51) # WS2812 LED pin PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) # ----------------------- GPS ---------------------------- define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_GPS_PORT_DEFAULT 3 define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 # ---------------------- COMPASS --------------------------- define HAL_PERIPH_ENABLE_MAG SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 define HAL_COMPASS_MAX_SENSORS 1 # --------------------- DPS310 --------------------------- define HAL_PERIPH_ENABLE_BARO SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ BARO DPS310 SPI:dps310 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE #define HAL_DISABLE_ADC_DRIVER TRUE PA0 VSENSE ADC1 SCALE(2) # -------------------- Buzzer+NeoPixels -------------------- define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY # Enable the sensor voltage pin PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH #GPS M9N PC11 M9EXTINT INPUT PC10 M9RST INPUT PC8 GPS_PPS_IN INPUT PC7 M9SB INPUT # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0