mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_ChibiOS: fixed for ZubaxGNSS build
This commit is contained in:
parent
e9af111b0c
commit
44f895ab16
@ -36,7 +36,7 @@
|
||||
/**
|
||||
* @brief STM32 GPIO static initialization data.
|
||||
*/
|
||||
#if defined(STM32F100_MCUCONF) || defined(STM32F103_MCUCONF)
|
||||
#if defined(STM32F100_MCUCONF) || defined(STM32F103_MCUCONF) || defined(STM32F105_MCUCONF)
|
||||
|
||||
const PALConfig pal_default_config =
|
||||
{
|
||||
@ -222,7 +222,7 @@ static void stm32_gpio_init(void) {
|
||||
* and before any other initialization.
|
||||
*/
|
||||
void __early_init(void) {
|
||||
#if !defined(STM32F100_MCUCONF) && !defined(STM32F103_MCUCONF)
|
||||
#if !defined(STM32F1)
|
||||
stm32_gpio_init();
|
||||
#endif
|
||||
stm32_clock_init();
|
||||
|
@ -43,6 +43,19 @@
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV4
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#elif STM32_HSECLK == 16000000U
|
||||
#define STM32_SW STM32_SW_PLL
|
||||
#define STM32_PLLSRC STM32_PLLSRC_PREDIV1
|
||||
#define STM32_PLLMUL_VALUE 9
|
||||
#define STM32_PREDIV1_VALUE 2
|
||||
#define STM32_PREDIV2_VALUE 4
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV2
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV4
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#define STM32_PLL2MUL_VALUE 16
|
||||
#define STM32_PLL3MUL_VALUE 16
|
||||
#elif STM32_HSECLK == 24000000U
|
||||
#define STM32_SW STM32_SW_HSE
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
@ -51,14 +64,11 @@
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV1
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV1
|
||||
#define STM32_ADCPRE STM32_ADCPRE_DIV2
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#else
|
||||
#error "Unsupported STM32F1xx clock frequency"
|
||||
#endif
|
||||
|
||||
#ifndef STM32_HPRE
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#endif
|
||||
|
||||
#define STM32_MCOSEL STM32_MCOSEL_NOCLOCK
|
||||
#define STM32_RTCSEL STM32_RTCSEL_HSEDIV
|
||||
#define STM32_PVD_ENABLE FALSE
|
||||
|
@ -15,14 +15,6 @@ 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
|
||||
|
@ -107,8 +107,6 @@ define HAL_NO_ROMFS_SUPPORT
|
||||
define HAL_UART_MIN_TX_SIZE 256
|
||||
define HAL_UART_MIN_RX_SIZE 128
|
||||
|
||||
define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
define HAL_UART_STACK_SIZE 256
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
|
||||
|
@ -213,6 +213,8 @@ class generic_pin(object):
|
||||
self.sig_dir = 'OUTPUT'
|
||||
elif l == 'I2C':
|
||||
self.sig_dir = 'OUTPUT'
|
||||
elif l == 'OTG':
|
||||
self.sig_dir = 'OUTPUT'
|
||||
else:
|
||||
error("Unknown signal type %s:%s for %s!" % (self.portpin, self.label, mcu_type))
|
||||
|
||||
@ -377,6 +379,8 @@ class generic_pin(object):
|
||||
if e in speed_values:
|
||||
v = e
|
||||
speed_str = "PIN_%s(%uU) |" % (v, self.pin)
|
||||
elif self.is_CS():
|
||||
speed_str = "PIN_SPEED_LOW(%uU) |" % (self.pin)
|
||||
else:
|
||||
speed_str = ""
|
||||
if self.af is not None:
|
||||
@ -390,6 +394,8 @@ class generic_pin(object):
|
||||
v = "AF_OD"
|
||||
else:
|
||||
v = "AF_PP"
|
||||
elif self.is_CS():
|
||||
v = "OUTPUT_PP"
|
||||
elif self.sig_dir == 'OUTPUT':
|
||||
if 'OPENDRAIN' in self.extra:
|
||||
v = 'OUTPUT_OD'
|
||||
|
Loading…
Reference in New Issue
Block a user