AP_HAL_ChibiOS: fixes for build with 20.3.x ChibiOS

This commit is contained in:
Andrew Tridgell 2020-01-20 14:20:30 +11:00
parent c2ad2d6090
commit 5b59445471
7 changed files with 128 additions and 54 deletions

View File

@ -576,7 +576,7 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
//TODO: Do timing calculations for FDCAN
can_->NBTP = ((timings.sjw << FDCAN_NBTP_NSJW_Pos) |
(timings.bs1 << FDCAN_NBTP_NTSEG1_Pos) |
(timings.bs2 << FDCAN_NBTP_TSEG2_Pos) |
(timings.bs2 << FDCAN_NBTP_NTSEG2_Pos) |
(timings.prescaler << FDCAN_NBTP_NBRP_Pos));
//RX Config

View File

@ -1563,7 +1563,7 @@ bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
*/
void RCOutput::serial_bit_irq(void)
{
systime_t now = chVTGetSystemTimeX();
systime_t now = AP_HAL::micros();
uint8_t bit = palReadLine(irq.line);
bool send_signal = false;

View File

@ -31,7 +31,7 @@
#include "hwdef.h"
#define _CHIBIOS_RT_CONF_
#define _CHIBIOS_RT_CONF_VER_6_0_
#define _CHIBIOS_RT_CONF_VER_6_1_
/*===========================================================================*/
/**
* @name System timers settings
@ -432,6 +432,39 @@ extern "C" {
#define CH_CFG_USE_PIPES FALSE
#endif
/**
* @brief Objects Caches APIs.
* @details If enabled then the objects caches APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#if !defined(CH_CFG_USE_OBJ_CACHES)
#define CH_CFG_USE_OBJ_CACHES TRUE
#endif
/**
* @brief Delegate threads APIs.
* @details If enabled then the delegate threads APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#if !defined(CH_CFG_USE_DELEGATES)
#define CH_CFG_USE_DELEGATES TRUE
#endif
/**
* @brief Jobs Queues APIs.
* @details If enabled then the jobs queues APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#if !defined(CH_CFG_USE_JOBS)
#define CH_CFG_USE_JOBS TRUE
#endif
/**
* @brief Dynamic Threads APIs.
* @details If enabled then the dynamic threads creation APIs are included

View File

@ -96,7 +96,7 @@ include $(CHIBIOS)/$(CHIBIOS_STARTUP_MK)
# HAL-OSAL files (optional).
include $(CHIBIOS)/os/hal/hal.mk
include $(CHIBIOS)/$(CHIBIOS_PLATFORM_MK)
include $(CHIBIOS)/os/hal/osal/rt/osal.mk
include $(CHIBIOS)/os/hal/osal/rt-nil/osal.mk
# RTOS files (optional).
include $(CHIBIOS)/os/rt/rt.mk
include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk

View File

@ -54,18 +54,18 @@ SECTIONS
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_start = .;
__init_array_base__ = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
__init_array_end__ = .;
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_start = .;
__fini_array_base__ = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
__fini_array_end__ = .;
} > flash
.text : ALIGN(4) SUBALIGN(4)
@ -138,25 +138,25 @@ SECTIONS
. = ALIGN(4);
PROVIDE(_textdata = LOADADDR(.data));
PROVIDE(_data = .);
_textdata_start = LOADADDR(.data);
_data_start = .;
__textdata_base__ = LOADADDR(.data);
__data_base__ = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
__data_end__ = .;
} > DATA_RAM AT > flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
__bss_base__ = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_bss_end = .;
__bss_end__ = .;
PROVIDE(end = .);
} > BSS_RAM

View File

@ -43,7 +43,8 @@
#pragma once
#define _CHIBIOS_HAL_CONF_
#define _CHIBIOS_HAL_CONF_VER_7_0_
#define _CHIBIOS_HAL_CONF_VER_7_1_
#include "mcuconf.h"
/**
@ -81,6 +82,13 @@
#define HAL_USE_DAC FALSE
#endif
/**
* @brief Enables the EFlash subsystem.
*/
#if !defined(HAL_USE_EFL) || defined(__DOXYGEN__)
#define HAL_USE_EFL FALSE
#endif
/**
* @brief Enables the GPT subsystem. We don't need it on most boards
* in ArduPilot, so it is disabled by default

View File

@ -18,30 +18,53 @@
*/
#pragma once
#ifndef STM32_LSECLK
#define STM32_LSECLK 32768U
#endif
#ifndef STM32_LSEDRV
#define STM32_LSEDRV (3U << 3U)
#define STM32_LSEDRV (3U << 3U)
#endif
/*
* STM32H7xx 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.
*/
#define STM32H7xx_MCUCONF
#define STM32H742_MCUCONF
#define STM32H743_MCUCONF
#define STM32H753_MCUCONF
#define STM32H745_MCUCONF
#define STM32H755_MCUCONF
#define STM32H747_MCUCONF
#define STM32H757_MCUCONF
/*
* General settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_SYS_CK_ENFORCED_VALUE STM32_HSICLK
#define STM32_TARGET_CORE 1
/*
* Memory attributes settings.
*/
#define STM32_NOCACHE_MPU_REGION MPU_REGION_6
#define STM32_NOCACHE_SRAM1_SRAM2 FALSE
#define STM32_NOCACHE_SRAM3 TRUE
/*
* PWR system settings.
* Reading STM32 Reference Manual is required.
* Reading STM32 Reference Manual is required, settings in PWR_CR3 are
* very critical.
* Register constants are taken from the ST header.
*/
#define STM32_VOS STM32_VOS_SCALE1
@ -136,7 +159,7 @@
#define STM32_PLL2_DIVN_VALUE 25
#define STM32_PLL2_DIVP_VALUE 2
#define STM32_PLL2_DIVQ_VALUE 4
#define STM32_PLL2_DIVR_VALUE 2
#define STM32_PLL2_DIVR_VALUE 4
#define STM32_PLL3_DIVN_VALUE 72
#define STM32_PLL3_DIVP_VALUE 3
@ -152,7 +175,7 @@
#define STM32_PLL2_DIVN_VALUE 12
#define STM32_PLL2_DIVP_VALUE 1
#define STM32_PLL2_DIVQ_VALUE 2
#define STM32_PLL2_DIVR_VALUE 2
#define STM32_PLL2_DIVR_VALUE 3
#define STM32_PLL3_DIVN_VALUE 48
#define STM32_PLL3_DIVP_VALUE 3
@ -218,8 +241,7 @@
#define STM32_RTCPRE_VALUE 8
#ifndef STM32_CKPERSEL
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
#endif
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL2_R_CK
#define STM32_QSPISEL STM32_QSPISEL_HCLK
#define STM32_FMCSEL STM32_QSPISEL_HCLK
#define STM32_SWPSEL STM32_SWPSEL_PCLK1
@ -245,7 +267,6 @@
#define STM32_LPTIM2SEL STM32_LPTIM2SEL_PCLK4
#define STM32_I2C4SEL STM32_I2C4SEL_PLL3_R_CK
#define STM32_LPUART1SEL STM32_LPUART1SEL_PCLK4
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK
/*
* IRQ system settings.
@ -261,9 +282,42 @@
#define STM32_IRQ_EXTI17_PRIORITY 15
#define STM32_IRQ_EXTI18_PRIORITY 6
#define STM32_IRQ_EXTI19_PRIORITY 6
#define STM32_IRQ_EXTI20_PRIORITY 6
#define STM32_IRQ_EXTI21_PRIORITY 15
#define STM32_IRQ_EXTI22_PRIORITY 15
#define STM32_IRQ_EXTI20_21_PRIORITY 6
#define STM32_IRQ_FDCAN1_PRIORITY 10
#define STM32_IRQ_FDCAN2_PRIORITY 10
#define STM32_IRQ_MDMA_PRIORITY 9
#define STM32_IRQ_QUADSPI1_PRIORITY 10
#define STM32_IRQ_SDMMC1_PRIORITY 9
#define STM32_IRQ_SDMMC2_PRIORITY 9
#define STM32_IRQ_TIM1_UP_PRIORITY 7
#define STM32_IRQ_TIM1_CC_PRIORITY 7
#define STM32_IRQ_TIM2_PRIORITY 7
#define STM32_IRQ_TIM3_PRIORITY 7
#define STM32_IRQ_TIM4_PRIORITY 7
#define STM32_IRQ_TIM5_PRIORITY 7
#define STM32_IRQ_TIM6_PRIORITY 7
#define STM32_IRQ_TIM7_PRIORITY 7
#define STM32_IRQ_TIM8_BRK_TIM12_PRIORITY 7
#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7
#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7
#define STM32_IRQ_TIM8_CC_PRIORITY 7
#define STM32_IRQ_TIM15_PRIORITY 7
#define STM32_IRQ_TIM16_PRIORITY 7
#define STM32_IRQ_TIM17_PRIORITY 7
#define STM32_IRQ_USART1_PRIORITY 12
#define STM32_IRQ_USART2_PRIORITY 12
#define STM32_IRQ_USART3_PRIORITY 12
#define STM32_IRQ_UART4_PRIORITY 12
#define STM32_IRQ_UART5_PRIORITY 12
#define STM32_IRQ_USART6_PRIORITY 12
#define STM32_IRQ_UART7_PRIORITY 12
#define STM32_IRQ_UART8_PRIORITY 12
/*
* ADC driver system settings.
@ -286,12 +340,8 @@
/*
* CAN driver system settings.
*/
#define STM32_CAN_USE_CAN1 FALSE
#define STM32_CAN_USE_CAN2 FALSE
#define STM32_CAN_USE_CAN3 FALSE
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
#define STM32_CAN_CAN2_IRQ_PRIORITY 11
#define STM32_CAN_CAN3_IRQ_PRIORITY 11
#define STM32_CAN_USE_FDCAN1 FALSE
#define STM32_CAN_USE_FDCAN2 FALSE
/*
* DAC driver system settings.
@ -315,22 +365,12 @@
#define STM32_GPT_USE_TIM6 FALSE
#define STM32_GPT_USE_TIM7 FALSE
#define STM32_GPT_USE_TIM8 FALSE
#define STM32_GPT_USE_TIM9 FALSE
#define STM32_GPT_USE_TIM11 FALSE
#define STM32_GPT_USE_TIM12 FALSE
#define STM32_GPT_USE_TIM13 FALSE
#define STM32_GPT_USE_TIM14 FALSE
#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_TIM6_IRQ_PRIORITY 7
#define STM32_GPT_TIM7_IRQ_PRIORITY 7
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
#define STM32_GPT_TIM9_IRQ_PRIORITY 7
#define STM32_GPT_TIM11_IRQ_PRIORITY 7
#define STM32_GPT_TIM12_IRQ_PRIORITY 7
#define STM32_GPT_TIM14_IRQ_PRIORITY 7
#define STM32_GPT_USE_TIM15 FALSE
#define STM32_GPT_USE_TIM16 FALSE
#define STM32_GPT_USE_TIM17 FALSE
/*
* I2C driver system settings.
@ -378,13 +418,6 @@
/*
* 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
#define STM32_PWM_TIM9_IRQ_PRIORITY 7
/*
* RTC driver system settings.