mirror of https://github.com/ArduPilot/ardupilot
153 lines
3.7 KiB
Plaintext
153 lines
3.7 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F100 STM32F100xB
|
|
|
|
FLASH_RESERVE_START_KB 4
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 3
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000
|
|
|
|
FLASH_SIZE_KB 64
|
|
|
|
# ChibiOS system timer
|
|
|
|
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER EMPTY EMPTY EMPTY EMPTY
|
|
define HAL_USE_UART TRUE
|
|
|
|
# UART connected to FMU, uses DMA
|
|
PA2 USART2_TX USART2 SPEED_HIGH
|
|
PA3 USART2_RX USART2 SPEED_HIGH
|
|
|
|
define STM32_UART_USE_USART1 FALSE
|
|
define STM32_UART_USE_USART2 TRUE
|
|
define STM32_UART_USE_USART3 FALSE
|
|
|
|
# UART for SBUS out, and RC in, no DMA
|
|
define HAL_USE_SERIAL TRUE
|
|
PB4 SBUS_OUT_EN OUTPUT LOW GPIO(1)
|
|
PB10 USART3_TX USART3 SPEED_HIGH LOW
|
|
PB11 USART3_RX USART3
|
|
|
|
define STM32_SERIAL_USE_USART1 TRUE
|
|
define STM32_SERIAL_USE_USART2 FALSE
|
|
define STM32_SERIAL_USE_USART3 TRUE
|
|
|
|
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(101)
|
|
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(102)
|
|
PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103)
|
|
PB9 TIM4_CH4 TIM4 PWM(4) GPIO(104)
|
|
PA6 TIM3_CH1 TIM3 PWM(5) GPIO(105)
|
|
PA7 TIM3_CH2 TIM3 PWM(6) GPIO(106)
|
|
PB0 TIM3_CH3 TIM3 PWM(7) GPIO(107)
|
|
PB1 TIM3_CH4 TIM3 PWM(8) GPIO(108)
|
|
|
|
# pins for detecting board type. On a pixhawk2 PC14 is pulled high,
|
|
# PC15 is pulled low. On a Pixhawk1 they are both floating
|
|
PC14 IO_HW_DETECT1 INPUT PULLDOWN
|
|
PC15 IO_HW_DETECT2 INPUT PULLUP
|
|
|
|
PB14 HEATER INPUT PULLUP GPIO(0)
|
|
|
|
# safety button and LED. These do not use the same names
|
|
# as those for FMU-only boards as we want to handle them specially
|
|
# inside the iofirmware
|
|
PB5 SAFETY_INPUT INPUT PULLDOWN
|
|
PB13 SAFETY_LED OUTPUT HIGH OPENDRAIN
|
|
|
|
# amber LED
|
|
PB15 AMBER_LED OUTPUT LOW OPENDRAIN
|
|
|
|
# green ring LED on cube
|
|
PA11 RING_LED OUTPUT LOW OPENDRAIN
|
|
|
|
# UART for DSM input
|
|
# TX side is for IO debug, and is unused
|
|
PA9 USART1_TX USART1 SPEED_HIGH
|
|
PA10 USART1_RX USART1 SPEED_HIGH
|
|
|
|
PC13 SPEKTRUM_PWR_EN OUTPUT LOW
|
|
define HAL_GPIO_PIN_SPEKTRUM_OUT PAL_LINE(GPIOA,10U)
|
|
|
|
PA8 RCIN INPUT SPEED_HIGH PULLDOWN # RC Input PPM
|
|
|
|
# analog inputs
|
|
PA4 VSERVO ADC1
|
|
PA5 VRSSI ADC1
|
|
define HAL_ADC_VSERVO_CHAN ADC_CHANNEL_IN4
|
|
define HAL_ADC_VRSSI_CHAN ADC_CHANNEL_IN5
|
|
define HAL_USE_ADC TRUE
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
#Manually define ICU settings
|
|
define HAL_USE_ICU TRUE
|
|
define STM32_ICU_USE_TIM1 TRUE
|
|
define RCIN_ICU_TIMER ICUD1
|
|
define RCIN_ICU_CHANNEL ICU_CHANNEL_1
|
|
define STM32_RCIN_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
|
|
|
|
#DMA Channel Not relevant for F1 series
|
|
define STM32_RCIN_DMA_CHANNEL 0
|
|
|
|
define HAL_USE_EMPTY_STORAGE 1
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
define HAL_INS_DEFAULT HAL_INS_NONE
|
|
define HAL_BARO_DEFAULT HAL_BARO_NONE
|
|
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
|
|
define HAL_NO_MONITOR_THREAD
|
|
define HAL_NO_RCOUT_THREAD
|
|
define AP_HAL_SHARED_DMA_ENABLED 0
|
|
|
|
#defined to turn off undef warnings
|
|
define __FPU_PRESENT 0
|
|
|
|
define HAL_USE_RTC FALSE
|
|
define HAL_NO_FLASH_SUPPORT TRUE
|
|
define HAL_NO_UARTDRIVER TRUE
|
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
|
define HAL_LOGGING_ENABLED 0
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
# reduce memory usage in RCInput
|
|
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
|
|
|
define IOMCU_FW TRUE
|
|
define AP_FASTBOOT_ENABLED 0
|
|
IOMCU_FW 1
|
|
MAIN_STACK 0x200
|
|
PROCESS_STACK 0x250
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
define AP_BOOTLOADER_FLASHING_ENABLED 0
|
|
|
|
define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0
|
|
define AP_RCPROTOCOL_PPMSUM_ENABLED 1
|
|
define AP_RCPROTOCOL_IBUS_ENABLED 1
|
|
define AP_RCPROTOCOL_SBUS_ENABLED 1
|
|
define AP_RCPROTOCOL_DSM_ENABLED 1
|
|
define AP_RCPROTOCOL_SUMD_ENABLED 1
|
|
define AP_RCPROTOCOL_SRXL_ENABLED 1
|
|
define AP_RCPROTOCOL_ST24_ENABLED 1
|
|
define AP_RCPROTOCOL_FPORT_ENABLED 1
|
|
|
|
AUTOBUILD_TARGETS iofirmware
|