mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
HAL_ChibiOS: add hwdef files to support IOMCU
This commit is contained in:
parent
f0b27c9b92
commit
e824a9c360
150
libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h
Normal file
150
libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h
Normal file
@ -0,0 +1,150 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
/*
|
||||
* STM32F103 drivers configuration.
|
||||
* The following settings override the default settings present in
|
||||
* the various device driver implementation headers.
|
||||
* Note that the settings for each driver only have effect if the whole
|
||||
* driver is enabled in halconf.h.
|
||||
*
|
||||
* IRQ priorities:
|
||||
* 15...0 Lowest...Highest.
|
||||
*
|
||||
* DMA priorities:
|
||||
* 0...3 Lowest...Highest.
|
||||
*/
|
||||
|
||||
/*
|
||||
* HAL driver system settings.
|
||||
*/
|
||||
#define STM32_NO_INIT FALSE
|
||||
#define STM32_HSI_ENABLED TRUE
|
||||
#define STM32_LSI_ENABLED FALSE
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#define STM32_LSE_ENABLED FALSE
|
||||
#define STM32_SW STM32_SW_HSE
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV1
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV1
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV2
|
||||
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
|
||||
#define STM32_RTCSEL STM32_RTCSEL_HSEDIV
|
||||
#define STM32_PVD_ENABLE FALSE
|
||||
#define STM32_PLS STM32_PLS_LEV0
|
||||
|
||||
/*
|
||||
* ADC driver system settings.
|
||||
*/
|
||||
#define STM32_ADC_ADC1_DMA_PRIORITY 2
|
||||
#define STM32_ADC_ADC1_IRQ_PRIORITY 6
|
||||
|
||||
/*
|
||||
* EXT driver system settings.
|
||||
*/
|
||||
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI17_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
|
||||
|
||||
/*
|
||||
* GPT driver system settings.
|
||||
*/
|
||||
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* I2C driver system settings.
|
||||
*/
|
||||
#define STM32_I2C_BUSY_TIMEOUT 50
|
||||
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
|
||||
#define STM32_I2C_I2C1_DMA_PRIORITY 3
|
||||
#define STM32_I2C_I2C2_DMA_PRIORITY 3
|
||||
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* ICU driver system settings.
|
||||
*/
|
||||
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* PWM driver system settings.
|
||||
*/
|
||||
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
|
||||
|
||||
/*
|
||||
* RTC driver system settings.
|
||||
*/
|
||||
#define STM32_RTC_IRQ_PRIORITY 15
|
||||
|
||||
/*
|
||||
* SERIAL driver system settings.
|
||||
*/
|
||||
#define STM32_SERIAL_USART1_PRIORITY 12
|
||||
#define STM32_SERIAL_USART2_PRIORITY 12
|
||||
#define STM32_SERIAL_USART3_PRIORITY 12
|
||||
|
||||
/*
|
||||
* SPI driver system settings.
|
||||
*/
|
||||
#define STM32_SPI_SPI1_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI2_DMA_PRIORITY 1
|
||||
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
|
||||
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* ST driver system settings.
|
||||
*/
|
||||
#define STM32_ST_IRQ_PRIORITY 8
|
||||
#ifndef STM32_ST_USE_TIMER
|
||||
#define STM32_ST_USE_TIMER 2
|
||||
#endif
|
||||
/*
|
||||
* UART driver system settings.
|
||||
*/
|
||||
#define STM32_UART_USART1_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART2_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART3_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART1_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART2_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART3_DMA_PRIORITY 0
|
||||
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
|
||||
|
||||
/*
|
||||
* WDG driver system settings.
|
||||
*/
|
||||
#define STM32_WDG_USE_IWDG FALSE
|
102
libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat
Normal file
102
libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat
Normal file
@ -0,0 +1,102 @@
|
||||
# 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
|
||||
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER EMPTY
|
||||
define HAL_USE_UART TRUE
|
||||
define STM32_UART_USE_USART2 TRUE
|
||||
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
|
||||
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 OUTPUT 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
|
||||
|
||||
PA8 INPUT PULLUP # RC Input PPM
|
||||
|
||||
#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 STM32_SERIAL_USE_USART2 TRUE
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
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 TIMER_THD_WA_SIZE 256
|
||||
define RCIN_THD_WA_SIZE 768
|
||||
define DEFAULT_TX_BUF_SIZE 0
|
||||
define DEFAULT_RX_BUF_SIZE 0
|
||||
#define CH_CFG_USE_DYNAMIC FALSE
|
||||
define SERIAL_BUFFERS_SIZE 0
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
#defined to turn off undef warnings
|
||||
define __FPU_PRESENT 0
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define CH_DBG_ENABLE_CHECKS TRUE
|
||||
define CH_DBG_ENABLE_ASSERTS TRUE
|
||||
define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
define CH_DBG_THREADS_PROFILING TRUE
|
||||
define HAL_NO_FLASH_SUPPORT TRUE
|
||||
define HAL_NO_UARTDRIVER TRUE
|
||||
define DISABLE_SERIAL_ESC_COMM TRUE
|
||||
define NO_DATAFLASH TRUE
|
||||
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
define IOMCU_FW TRUE
|
||||
|
||||
MAIN_STACK 0x200
|
||||
PROCESS_STACK 0x250
|
34
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py
Normal file
34
libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F100xB.py
Normal file
@ -0,0 +1,34 @@
|
||||
#!/usr/bin/env python
|
||||
'''
|
||||
these tables are generated from the STM32 datasheets for the
|
||||
STM32F100xB
|
||||
'''
|
||||
|
||||
# additional build information for ChibiOS
|
||||
build = {
|
||||
"CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f1xx.mk",
|
||||
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F1xx/platform.mk",
|
||||
"CHPRINTF_USE_FLOAT" : 'no',
|
||||
"USE_FPU" : 'no'
|
||||
}
|
||||
|
||||
pincount = {
|
||||
'A': 16,
|
||||
'B': 16,
|
||||
'C': 16,
|
||||
'D': 16,
|
||||
'E': 16
|
||||
}
|
||||
|
||||
# MCU parameters
|
||||
mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFFF7E8,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 8,
|
||||
|
||||
}
|
Loading…
Reference in New Issue
Block a user