mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_HAL_ChibiOS: build fixes for ChibiOS 20.3.x
This commit is contained in:
parent
c26f49fb0a
commit
e1d71486e4
@ -161,8 +161,8 @@ void hal_chibios_set_priority(uint8_t priority)
|
||||
{
|
||||
chSysLock();
|
||||
#if CH_CFG_USE_MUTEXES == TRUE
|
||||
if ((daemon_task->prio == daemon_task->realprio) || (priority > daemon_task->prio)) {
|
||||
daemon_task->prio = priority;
|
||||
if ((daemon_task->hdr.pqueue.prio == daemon_task->realprio) || (priority > daemon_task->hdr.pqueue.prio)) {
|
||||
daemon_task->hdr.pqueue.prio = priority;
|
||||
}
|
||||
daemon_task->realprio = priority;
|
||||
#endif
|
||||
|
@ -762,7 +762,7 @@ void Scheduler::check_stack_free(void)
|
||||
if (stack_free(tp->wabase) < min_stack) {
|
||||
// use task priority for line number. This allows us to
|
||||
// identify the task fairly reliably
|
||||
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, tp->prio);
|
||||
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, tp->realprio);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -120,7 +120,7 @@ void UARTDriver::uart_thread()
|
||||
// change the thread priority if requested - if unbuffered it should only have higher priority than the owner so that
|
||||
// handoff occurs immediately
|
||||
if (mask & EVT_TRANSMIT_UNBUFFERED) {
|
||||
chThdSetPriority(unbuffered_writes ? MIN(_uart_owner_thd->prio + 1, APM_UART_UNBUFFERED_PRIORITY) : APM_UART_PRIORITY);
|
||||
chThdSetPriority(unbuffered_writes ? MIN(_uart_owner_thd->realprio + 1, APM_UART_UNBUFFERED_PRIORITY) : APM_UART_PRIORITY);
|
||||
}
|
||||
#ifndef HAL_UART_NODMA
|
||||
osalDbgAssert(!dma_handle || !dma_handle->is_locked(), "DMA handle is already locked");
|
||||
|
@ -357,14 +357,14 @@ void Util::thread_info(ExpandingString &str)
|
||||
}
|
||||
#if HAL_ENABLE_THREAD_STATISTICS
|
||||
str.printf("%-13.13s PRI=%3u sp=%p STACK=%4u/%4u MIN=%4u AVG=%4u MAX=%4u\n",
|
||||
tp->name, unsigned(tp->prio), tp->wabase,
|
||||
tp->name, unsigned(tp->realprio), tp->wabase,
|
||||
unsigned(stack_free(tp->wabase)), unsigned(total_stack), unsigned(RTC2US(STM32_HSECLK, tp->stats.best)),
|
||||
unsigned(RTC2US(STM32_HSECLK, uint32_t(tp->stats.cumulative / uint64_t(tp->stats.n)))),
|
||||
unsigned(RTC2US(STM32_HSECLK, tp->stats.worst)));
|
||||
chTMObjectInit(&tp->stats); // reset counters to zero
|
||||
#else
|
||||
str.printf("%-13.13s PRI=%3u sp=%p STACK=%u/%u\n",
|
||||
tp->name, unsigned(tp->prio), tp->wabase,
|
||||
tp->name, unsigned(tp->realprio), tp->wabase,
|
||||
unsigned(stack_free(tp->wabase)), unsigned(total_stack));
|
||||
#endif
|
||||
}
|
||||
|
@ -7,7 +7,7 @@
|
||||
/ FatFs - FAT file system module configuration file
|
||||
/---------------------------------------------------------------------------*/
|
||||
|
||||
#define FFCONF_DEF 87030 /* Revision ID */
|
||||
#define FFCONF_DEF 80196 /* Revision ID */
|
||||
|
||||
/*---------------------------------------------------------------------------/
|
||||
/ Function Configurations
|
||||
@ -126,6 +126,12 @@
|
||||
/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1.
|
||||
/ This option also affects behavior of string I/O functions. */
|
||||
|
||||
#define FF_LFN_BUF 255
|
||||
#define FF_SFN_BUF 12
|
||||
/* This set of options defines size of file name members in the FILINFO structure
|
||||
/ which is used to read out directory items. These values should be suffcient for
|
||||
/ the file names to read. The maximum possible length of the read file name depends
|
||||
/ on character encoding. When LFN is not enabled, these options have no effect. */
|
||||
|
||||
#define FF_STRF_ENCODE 3
|
||||
/* When _LFN_UNICODE == 1, this option selects the character encoding ON THE FILE to
|
||||
@ -183,6 +189,14 @@
|
||||
/ to variable sector size and GET_SECTOR_SIZE command must be implemented to the
|
||||
/ disk_ioctl() function. */
|
||||
|
||||
#define FF_LBA64 0
|
||||
/* This option switches support for 64-bit LBA. (0:Disable or 1:Enable)
|
||||
/ To enable the 64-bit LBA, also exFAT needs to be enabled. (FF_FS_EXFAT == 1) */
|
||||
|
||||
|
||||
#define FF_MIN_GPT 0x100000000
|
||||
/* Minimum number of sectors to switch GPT format to create partition in f_mkfs and
|
||||
/ f_fdisk function. 0x100000000 max. This option has no effect when FF_LBA64 == 0. */
|
||||
|
||||
#define FF_USE_TRIM 0
|
||||
/* This option switches support of ATA-TRIM. (0:Disable or 1:Enable)
|
||||
@ -247,7 +261,7 @@
|
||||
|
||||
|
||||
#define FF_FS_REENTRANT 0
|
||||
#define FF_FS_TIMEOUT chTimeMS2I(1000)
|
||||
#define FF_FS_TIMEOUT MS2ST(1000)
|
||||
#define FF_SYNC_t semaphore_t*
|
||||
/* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
|
||||
/ module itself. Note that regardless of this option, file access to different
|
||||
|
@ -206,20 +206,21 @@
|
||||
/*
|
||||
* 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 15
|
||||
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI20_IRQ_PRIORITY 6
|
||||
#define STM32_EXT_EXTI21_IRQ_PRIORITY 15
|
||||
#define STM32_EXT_EXTI22_IRQ_PRIORITY 15
|
||||
#define STM32_IRQ_EXTI0_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI1_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI2_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI3_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI4_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI5_9_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI10_15_PRIORITY 6
|
||||
#define STM32_IRQ_EXTI16_PRIORITY 6
|
||||
#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_EXTI23_PRIORITY 15
|
||||
|
||||
/*
|
||||
* GPT driver system settings.
|
||||
@ -395,15 +396,28 @@
|
||||
#define STM32_ST_USE_TIMER 2
|
||||
#endif
|
||||
|
||||
#define STM32_IRQ_TIM1_UP_PRIORITY 7
|
||||
#define STM32_IRQ_TIM1_UP_TIM10_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_TIM1_BRK_TIM9_PRIORITY 7
|
||||
#define STM32_IRQ_TIM8_UP_TIM13_PRIORITY 7
|
||||
#define STM32_IRQ_TIM8_TRGCO_TIM14_PRIORITY 7
|
||||
#define STM32_IRQ_TIM1_TRGCO_TIM11_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
|
||||
|
||||
/*
|
||||
* 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_UART4_IRQ_PRIORITY 12
|
||||
#define STM32_UART_UART5_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART6_IRQ_PRIORITY 12
|
||||
#define STM32_UART_USART1_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART2_DMA_PRIORITY 0
|
||||
#define STM32_UART_USART3_DMA_PRIORITY 0
|
||||
@ -412,6 +426,23 @@
|
||||
#define STM32_UART_USART6_DMA_PRIORITY 0
|
||||
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
|
||||
|
||||
#define STM32_IRQ_UART1_PRIORITY 12
|
||||
#define STM32_IRQ_UART2_PRIORITY 12
|
||||
#define STM32_IRQ_UART3_PRIORITY 12
|
||||
#define STM32_IRQ_UART4_PRIORITY 12
|
||||
#define STM32_IRQ_UART5_PRIORITY 12
|
||||
#define STM32_IRQ_UART6_PRIORITY 12
|
||||
#define STM32_IRQ_UART7_PRIORITY 12
|
||||
#define STM32_IRQ_UART8_PRIORITY 12
|
||||
#define STM32_IRQ_USART1_PRIORITY 12
|
||||
#define STM32_IRQ_USART2_PRIORITY 12
|
||||
#define STM32_IRQ_USART3_PRIORITY 12
|
||||
#define STM32_IRQ_USART4_PRIORITY 12
|
||||
#define STM32_IRQ_USART5_PRIORITY 12
|
||||
#define STM32_IRQ_USART6_PRIORITY 12
|
||||
#define STM32_IRQ_USART7_PRIORITY 12
|
||||
#define STM32_IRQ_USART8_PRIORITY 12
|
||||
|
||||
/*
|
||||
* USB driver system settings.
|
||||
*/
|
||||
|
@ -241,6 +241,7 @@
|
||||
#define STM32_RTCPRE_VALUE 8
|
||||
#ifndef STM32_CKPERSEL
|
||||
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
|
||||
#endif
|
||||
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL2_R_CK
|
||||
#define STM32_QSPISEL STM32_QSPISEL_HCLK
|
||||
#define STM32_FMCSEL STM32_QSPISEL_HCLK
|
||||
@ -520,6 +521,8 @@
|
||||
#define STM32_UART_UART8_DMA_PRIORITY 0
|
||||
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
|
||||
|
||||
#define STM32_IRQ_LPUART1_PRIORITY 12
|
||||
|
||||
/*
|
||||
* USB driver system settings.
|
||||
*/
|
||||
|
@ -821,6 +821,9 @@ def write_mcu_config(f):
|
||||
#define CH_CFG_USE_MAILBOXES FALSE
|
||||
#define CH_CFG_USE_FACTORY FALSE
|
||||
#define CH_CFG_USE_MEMCORE FALSE
|
||||
#define CH_CFG_USE_DELEGATES FALSE
|
||||
#define CH_CFG_USE_JOBS FALSE
|
||||
#define CH_CFG_USE_OBJ_CACHES FALSE
|
||||
#define HAL_USE_I2C FALSE
|
||||
#define HAL_USE_PWM FALSE
|
||||
#define CH_DBG_ENABLE_STACK_CHECK FALSE
|
||||
|
@ -80,7 +80,7 @@ static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fa
|
||||
pd.fault_addr = fault_addr;
|
||||
thread_t *tp = chThdGetSelfX();
|
||||
if (tp) {
|
||||
pd.fault_thd_prio = tp->prio;
|
||||
pd.fault_thd_prio = tp->hdr.pqueue.prio;
|
||||
// get first 4 bytes of the name, but only of first fault
|
||||
if (tp->name && pd.thread_name4[0] == 0) {
|
||||
strncpy_noterm(pd.thread_name4, tp->name, 4);
|
||||
|
Loading…
Reference in New Issue
Block a user