123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109 |
- # hw definition file for processing by chibios_pins.py
- # MCU class and specific type
- MCU STM32F103 STM32F103xB
- FLASH_RESERVE_START_KB 0
- FLASH_BOOTLOADER_LOAD_KB 25
- # board ID for firmware load
- APJ_BOARD_ID 1000
- # setup build for a peripheral firmware
- env AP_PERIPH 1
- # crystal frequency
- OSCILLATOR_HZ 8000000
- define STM32_SW STM32_SW_PLL
- define STM32_PLLSRC STM32_PLLSRC_HSE
- define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1
- define STM32_PLLMUL_VALUE 9
- define STM32_PPRE1 STM32_PPRE1_DIV2
- define STM32_PPRE2 STM32_PPRE2_DIV2
- define STM32_ADCPRE STM32_ADCPRE_DIV4
- define CH_CFG_ST_FREQUENCY 1000
- # assume 128k flash part
- FLASH_SIZE_KB 128
- STDOUT_SERIAL SD1
- STDOUT_BAUDRATE 57600
- # board voltage
- STM32_VDD 330U
- # order of UARTs
- UART_ORDER
- define HAL_USE_UART FALSE
- PA4 LED_BOOTLOADER OUTPUT LOW
- define HAL_LED_ON 1
- # USART1
- PA9 USART1_TX USART1 SPEED_HIGH
- PA10 USART1_RX USART1 SPEED_HIGH
- # USART2
- PA2 USART2_TX USART2 SPEED_HIGH
- PA3 USART2_RX USART2 SPEED_HIGH
- define HAL_USE_SERIAL TRUE
- define STM32_SERIAL_USE_USART1 TRUE
- define STM32_SERIAL_USE_USART2 TRUE
- define STM32_SERIAL_USE_USART3 FALSE
- define HAL_NO_GPIO_IRQ
- define CH_CFG_ST_TIMEDELTA 0
- #define CH_CFG_USE_DYNAMIC FALSE
- define SERIAL_BUFFERS_SIZE 32
- define HAL_USE_EMPTY_IO TRUE
- define PORT_INT_REQUIRED_STACK 64
- # avoid timer and RCIN threads to save memory
- define HAL_NO_TIMER_THREAD
- define HAL_NO_RCIN_THREAD
- #defined to turn off undef warnings
- define __FPU_PRESENT 0
- define HAL_USE_RTC FALSE
- define DISABLE_SERIAL_ESC_COMM TRUE
- define NO_DATAFLASH TRUE
- define DMA_RESERVE_SIZE 0
- define PERIPH_FW TRUE
- MAIN_STACK 0x800
- PROCESS_STACK 0x800
- define HAL_DISABLE_LOOP_DELAY
- define HAL_USE_EMPTY_STORAGE 1
- define HAL_STORAGE_SIZE 16384
- # enable CAN support
- PA11 CAN_RX CAN
- PA12 CAN_TX CAN
- define HAL_USE_CAN TRUE
- define STM32_CAN_USE_CAN1 TRUE
- define CAN_APP_VERSION_MAJOR 1
- define CAN_APP_VERSION_MINOR 0
- define CAN_APP_NODE_NAME "org.ardupilot.ap_periph"
- # start with a fixed node ID so the board is usable without DNA
- define HAL_CAN_DEFAULT_NODE_ID 117
- # make bl baudrate match debug baudrate for easier debugging
- define BOOTLOADER_BAUDRATE 57600
- # use a small bootloader timeout
- define HAL_BOOTLOADER_TIMEOUT 1000
- # use PB6 (normally I2C1_SCL) as "hold in bootloader" pin
- # this has a hw pullup, so if we set it as input floating
- # and look for it low then we know user has pulled it down and
- # want to stay in the bootloader
- PB6 STAY_IN_BOOTLOADER INPUT FLOATING
|