HAL_ChibiOS: fixes for ChibiOS version update

This commit is contained in:
Andrew Tridgell 2018-08-02 15:23:10 +10:00
parent c5f3beb297
commit 7aba99e229
8 changed files with 26 additions and 8 deletions

View File

@ -18,8 +18,6 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#if HAL_USE_EXT == TRUE
using namespace ChibiOS;
// GPIO pin table from hwdef.dat
@ -193,4 +191,3 @@ void pal_interrupt_cb(void *arg)
}
}
#endif // HAL_USE_EXT

View File

@ -686,7 +686,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
dmaStreamEnable(txdma);
uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500;
chVTSet(&tx_timeout, US2ST(timeout_us), handle_tx_timeout, this);
chVTSet(&tx_timeout, chTimeUS2I(timeout_us), handle_tx_timeout, this);
}
/*

View File

@ -31,7 +31,7 @@
#include "hwdef.h"
#define _CHIBIOS_RT_CONF_
#define _CHIBIOS_RT_CONF_VER_5_0_
#define _CHIBIOS_RT_CONF_VER_5_1_
/*===========================================================================*/
/**
* @name System timers settings
@ -39,6 +39,13 @@
*/
/*===========================================================================*/
#ifdef HAL_CHIBIOS_ENABLE_ASSERTS
#define CH_DBG_ENABLE_ASSERTS TRUE
#define CH_DBG_ENABLE_CHECKS TRUE
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
#define CH_DBG_ENABLE_STACK_CHECK TRUE
#endif
/**
* @brief System time counter resolution.
* @note Allowed values are 16 or 32 bits.
@ -359,7 +366,9 @@
*
* @note The default is @p TRUE.
*/
#ifndef CH_CFG_USE_OBJ_FIFOS
#define CH_CFG_USE_OBJ_FIFOS TRUE
#endif
/**
* @brief Dynamic Threads APIs.
@ -390,7 +399,9 @@
*
* @note The default is @p FALSE.
*/
#ifndef CH_CFG_USE_FACTORY
#define CH_CFG_USE_FACTORY TRUE
#endif
/**
* @brief Maximum length for object names.

View File

@ -213,6 +213,11 @@ CPPWARN = -Wall -Wextra -Wundef
# List all user C define here, like -D_DEBUG=1
UDEFS = $(FATFS_FLAGS) -DHAL_BOARD_NAME=\"$(HAL_BOARD_NAME)\"
ifeq ($(ENABLE_ASSERTS),yes)
UDEFS += -DHAL_CHIBIOS_ENABLE_ASSERTS
ASXFLAGS += -DHAL_CHIBIOS_ENABLE_ASSERTS
endif
# Define ASM defines here
UADEFS =

View File

@ -124,6 +124,10 @@ LDFLAGS = $(MCFLAGS) $(OPT) -nostartfiles $(LLIBDIR) -Wl,-Map=$(BUILDDIR)/$(PR
# provide a marker for ArduPilot build options in ChibiOS
CFLAGS += -D_ARDUPILOT_
ifeq ($(ENABLE_ASSERTS),yes)
ASXFLAGS += -DHAL_CHIBIOS_ENABLE_ASSERTS
endif
# Thumb interwork enabled only if needed because it kills performance.
ifneq ($(strip $(TSRC)),)
CFLAGS += -DTHUMB_PRESENT
@ -163,7 +167,6 @@ CPPFLAGS += -MD -MP -MF .dep/$(@F).d
# Paths where to search for sources
VPATH = $(SRCPATHS)
ifndef ECHO
T := $(shell $(MAKE) $(MAKECMDGOALS) --no-print-directory \
-nrRf $(firstword $(MAKEFILE_LIST)) \

View File

@ -283,7 +283,7 @@ bool stm32_flash_erasepage(uint32_t page)
stm32_flash_wait_idle();
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
dmaBufferInvalidate(stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
cacheBufferInvalidate(stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
#endif
stm32_flash_lock();

View File

@ -266,7 +266,7 @@ void peripheral_power_enable(void)
uint8_t i;
for (i=0; i<100; i++) {
// use a loop as this may be a 16 bit timer
chThdSleep(MS2ST(1));
chThdSleep(chTimeMS2I(1));
}
#ifdef HAL_GPIO_PIN_nVDD_5V_PERIPH_EN
palWriteLine(HAL_GPIO_PIN_nVDD_5V_PERIPH_EN, 0);

View File

@ -447,6 +447,7 @@ def write_mcu_config(f):
#define CH_CFG_USE_WAITEXIT FALSE
#define CH_CFG_USE_DYNAMIC FALSE
#define CH_CFG_USE_MEMPOOLS FALSE
#define CH_CFG_USE_OBJ_FIFOS FALSE
#define CH_DBG_FILL_THREADS FALSE
#define CH_CFG_USE_SEMAPHORES FALSE
#define CH_CFG_USE_HEAP FALSE
@ -456,6 +457,7 @@ def write_mcu_config(f):
#define CH_CFG_USE_EVENTS_TIMEOUT FALSE
#define CH_CFG_USE_MESSAGES FALSE
#define CH_CFG_USE_MAILBOXES FALSE
#define CH_CFG_USE_FACTORY FALSE
#define HAL_USE_I2C FALSE
#define HAL_USE_PWM FALSE
''')