HAL_ChibiOS: update chconf.h for VER_6_0 API
This commit is contained in:
parent
903926e63b
commit
247bb433ec
@ -31,7 +31,7 @@
|
||||
#include "hwdef.h"
|
||||
|
||||
#define _CHIBIOS_RT_CONF_
|
||||
#define _CHIBIOS_RT_CONF_VER_5_1_
|
||||
#define _CHIBIOS_RT_CONF_VER_6_0_
|
||||
/*===========================================================================*/
|
||||
/**
|
||||
* @name System timers settings
|
||||
@ -76,13 +76,17 @@
|
||||
* @brief Time intervals data size.
|
||||
* @note Allowed values are 16, 32 or 64 bits.
|
||||
*/
|
||||
#if !defined(CH_CFG_INTERVALS_SIZE)
|
||||
#define CH_CFG_INTERVALS_SIZE 32
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Time types data size.
|
||||
* @note Allowed values are 16 or 32 bits.
|
||||
*/
|
||||
#if !defined(CH_CFG_TIME_TYPES_SIZE)
|
||||
#define CH_CFG_TIME_TYPES_SIZE 32
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Time delta constant for the tick-less mode.
|
||||
@ -128,7 +132,9 @@
|
||||
* @note The round robin preemption is not supported in tickless mode and
|
||||
* must be set to zero in that case.
|
||||
*/
|
||||
#if !defined(CH_CFG_TIME_QUANTUM)
|
||||
#define CH_CFG_TIME_QUANTUM 0
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Managed RAM size.
|
||||
@ -141,7 +147,9 @@
|
||||
* provide the @p __heap_base__ and @p __heap_end__ symbols.
|
||||
* @note Requires @p CH_CFG_USE_MEMCORE.
|
||||
*/
|
||||
#if !defined(CH_CFG_MEMCORE_SIZE)
|
||||
#define CH_CFG_MEMCORE_SIZE 0
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Idle thread automatic spawn suppression.
|
||||
@ -150,7 +158,7 @@
|
||||
* function becomes the idle thread and must implement an
|
||||
* infinite loop.
|
||||
*/
|
||||
#ifndef CH_CFG_NO_IDLE_THREAD
|
||||
#if !defined(CH_CFG_NO_IDLE_THREAD)
|
||||
#define CH_CFG_NO_IDLE_THREAD FALSE
|
||||
#endif
|
||||
|
||||
@ -171,7 +179,7 @@
|
||||
* @note This is not related to the compiler optimization options.
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_OPTIMIZE_SPEED
|
||||
#if !defined(CH_CFG_OPTIMIZE_SPEED)
|
||||
#define CH_CFG_OPTIMIZE_SPEED TRUE
|
||||
#endif
|
||||
|
||||
@ -191,7 +199,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_TM
|
||||
#if !defined(CH_CFG_USE_TM)
|
||||
#define CH_CFG_USE_TM TRUE
|
||||
#endif
|
||||
|
||||
@ -201,7 +209,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_REGISTRY
|
||||
#if !defined(CH_CFG_USE_REGISTRY)
|
||||
#define CH_CFG_USE_REGISTRY TRUE
|
||||
#endif
|
||||
|
||||
@ -212,7 +220,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_WAITEXIT
|
||||
#if !defined(CH_CFG_USE_WAITEXIT)
|
||||
#define CH_CFG_USE_WAITEXIT TRUE
|
||||
#endif
|
||||
|
||||
@ -222,7 +230,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_SEMAPHORES
|
||||
#if !defined(CH_CFG_USE_SEMAPHORES)
|
||||
#define CH_CFG_USE_SEMAPHORES TRUE
|
||||
#endif
|
||||
|
||||
@ -235,7 +243,9 @@
|
||||
* requirements.
|
||||
* @note Requires @p CH_CFG_USE_SEMAPHORES.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_SEMAPHORES_PRIORITY)
|
||||
#define CH_CFG_USE_SEMAPHORES_PRIORITY FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Mutexes APIs.
|
||||
@ -243,7 +253,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_MUTEXES
|
||||
#if !defined(CH_CFG_USE_MUTEXES)
|
||||
#define CH_CFG_USE_MUTEXES TRUE
|
||||
#endif
|
||||
|
||||
@ -255,7 +265,9 @@
|
||||
* @note The default is @p FALSE.
|
||||
* @note Requires @p CH_CFG_USE_MUTEXES.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_MUTEXES_RECURSIVE)
|
||||
#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Conditional Variables APIs.
|
||||
@ -265,7 +277,7 @@
|
||||
* @note The default is @p TRUE.
|
||||
* @note Requires @p CH_CFG_USE_MUTEXES.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_CONDVARS
|
||||
#if !defined(CH_CFG_USE_CONDVARS)
|
||||
#define CH_CFG_USE_CONDVARS TRUE
|
||||
#endif
|
||||
|
||||
@ -277,7 +289,7 @@
|
||||
* @note The default is @p TRUE.
|
||||
* @note Requires @p CH_CFG_USE_CONDVARS.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_CONDVARS_TIMEOUT
|
||||
#if !defined(CH_CFG_USE_CONDVARS_TIMEOUT)
|
||||
#define CH_CFG_USE_CONDVARS_TIMEOUT TRUE
|
||||
#endif
|
||||
|
||||
@ -287,7 +299,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_EVENTS
|
||||
#if !defined(CH_CFG_USE_EVENTS)
|
||||
#define CH_CFG_USE_EVENTS TRUE
|
||||
#endif
|
||||
|
||||
@ -299,7 +311,7 @@
|
||||
* @note The default is @p TRUE.
|
||||
* @note Requires @p CH_CFG_USE_EVENTS.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_EVENTS_TIMEOUT
|
||||
#if !defined(CH_CFG_USE_EVENTS_TIMEOUT)
|
||||
#define CH_CFG_USE_EVENTS_TIMEOUT TRUE
|
||||
#endif
|
||||
|
||||
@ -310,7 +322,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_MESSAGES
|
||||
#if !defined(CH_CFG_USE_MESSAGES)
|
||||
#define CH_CFG_USE_MESSAGES TRUE
|
||||
#endif
|
||||
|
||||
@ -323,7 +335,9 @@
|
||||
* requirements.
|
||||
* @note Requires @p CH_CFG_USE_MESSAGES.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_MESSAGES_PRIORITY)
|
||||
#define CH_CFG_USE_MESSAGES_PRIORITY FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Mailboxes APIs.
|
||||
@ -333,7 +347,7 @@
|
||||
* @note The default is @p TRUE.
|
||||
* @note Requires @p CH_CFG_USE_SEMAPHORES.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_MAILBOXES
|
||||
#if !defined(CH_CFG_USE_MAILBOXES)
|
||||
#define CH_CFG_USE_MAILBOXES TRUE
|
||||
#endif
|
||||
|
||||
@ -344,7 +358,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_MEMCORE
|
||||
#if !defined(CH_CFG_USE_MEMCORE)
|
||||
#define CH_CFG_USE_MEMCORE TRUE
|
||||
#endif
|
||||
|
||||
@ -358,7 +372,7 @@
|
||||
* @p CH_CFG_USE_SEMAPHORES.
|
||||
* @note Mutexes are recommended.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_HEAP
|
||||
#if !defined(CH_CFG_USE_HEAP)
|
||||
#define CH_CFG_USE_HEAP TRUE
|
||||
#endif
|
||||
|
||||
@ -369,7 +383,7 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_MEMPOOLS
|
||||
#if !defined(CH_CFG_USE_MEMPOOLS)
|
||||
#define CH_CFG_USE_MEMPOOLS TRUE
|
||||
#endif
|
||||
|
||||
@ -380,10 +394,21 @@
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_OBJ_FIFOS
|
||||
#if !defined(CH_CFG_USE_OBJ_FIFOS)
|
||||
#define CH_CFG_USE_OBJ_FIFOS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Pipes APIs.
|
||||
* @details If enabled then the pipes APIs are included
|
||||
* in the kernel.
|
||||
*
|
||||
* @note The default is @p TRUE.
|
||||
*/
|
||||
#if !defined(CH_CFG_USE_PIPES)
|
||||
#define CH_CFG_USE_PIPES TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Dynamic Threads APIs.
|
||||
* @details If enabled then the dynamic threads creation APIs are included
|
||||
@ -393,7 +418,7 @@
|
||||
* @note Requires @p CH_CFG_USE_WAITEXIT.
|
||||
* @note Requires @p CH_CFG_USE_HEAP and/or @p CH_CFG_USE_MEMPOOLS.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_DYNAMIC
|
||||
#if !defined(CH_CFG_USE_DYNAMIC)
|
||||
#define CH_CFG_USE_DYNAMIC TRUE
|
||||
#endif
|
||||
|
||||
@ -413,7 +438,7 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_CFG_USE_FACTORY
|
||||
#if !defined(CH_CFG_USE_FACTORY)
|
||||
#define CH_CFG_USE_FACTORY TRUE
|
||||
#endif
|
||||
|
||||
@ -422,32 +447,51 @@
|
||||
* @details If the specified length is zero then the name is stored by
|
||||
* pointer but this could have unintended side effects.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_MAX_NAMES_LENGTH)
|
||||
#define CH_CFG_FACTORY_MAX_NAMES_LENGTH 8
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables the registry of generic objects.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_OBJECTS_REGISTRY)
|
||||
#define CH_CFG_FACTORY_OBJECTS_REGISTRY TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables factory for generic buffers.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_GENERIC_BUFFERS)
|
||||
#define CH_CFG_FACTORY_GENERIC_BUFFERS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables factory for semaphores.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_SEMAPHORES)
|
||||
#define CH_CFG_FACTORY_SEMAPHORES TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables factory for mailboxes.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_MAILBOXES)
|
||||
#define CH_CFG_FACTORY_MAILBOXES TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables factory for objects FIFOs.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_OBJ_FIFOS)
|
||||
#define CH_CFG_FACTORY_OBJ_FIFOS TRUE
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Enables factory for Pipes.
|
||||
*/
|
||||
#if !defined(CH_CFG_FACTORY_PIPES) || defined(__DOXYGEN__)
|
||||
#define CH_CFG_FACTORY_PIPES TRUE
|
||||
#endif
|
||||
|
||||
/** @} */
|
||||
|
||||
@ -463,7 +507,7 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_DBG_STATISTICS
|
||||
#if !defined(CH_DBG_STATISTICS)
|
||||
#define CH_DBG_STATISTICS TRUE
|
||||
#endif
|
||||
|
||||
@ -474,7 +518,7 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_DBG_SYSTEM_STATE_CHECK
|
||||
#if !defined(CH_DBG_SYSTEM_STATE_CHECK)
|
||||
#define CH_DBG_SYSTEM_STATE_CHECK FALSE
|
||||
#endif
|
||||
|
||||
@ -485,11 +529,10 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_DBG_ENABLE_CHECKS
|
||||
#if !defined(CH_DBG_ENABLE_CHECKS)
|
||||
#define CH_DBG_ENABLE_CHECKS FALSE
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @brief Debug option, consistency checks.
|
||||
* @details If enabled then all the assertions in the kernel code are
|
||||
@ -498,7 +541,7 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_DBG_ENABLE_ASSERTS
|
||||
#if !defined(CH_DBG_ENABLE_ASSERTS)
|
||||
#define CH_DBG_ENABLE_ASSERTS FALSE
|
||||
#endif
|
||||
|
||||
@ -508,14 +551,18 @@
|
||||
*
|
||||
* @note The default is @p CH_DBG_TRACE_MASK_DISABLED.
|
||||
*/
|
||||
#if !defined(CH_DBG_TRACE_MASK)
|
||||
#define CH_DBG_TRACE_MASK CH_DBG_TRACE_MASK_DISABLED
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Trace buffer entries.
|
||||
* @note The trace buffer is only allocated if @p CH_DBG_TRACE_MASK is
|
||||
* different from @p CH_DBG_TRACE_MASK_DISABLED.
|
||||
*/
|
||||
#if !defined(CH_DBG_TRACE_BUFFER_SIZE)
|
||||
#define CH_DBG_TRACE_BUFFER_SIZE 128
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief Debug option, stack checks.
|
||||
@ -527,7 +574,7 @@
|
||||
* @note The default failure mode is to halt the system with the global
|
||||
* @p panic_msg variable set to @p NULL.
|
||||
*/
|
||||
#ifndef CH_DBG_ENABLE_STACK_CHECK
|
||||
#if !defined(CH_DBG_ENABLE_STACK_CHECK)
|
||||
#define CH_DBG_ENABLE_STACK_CHECK FALSE
|
||||
#endif
|
||||
|
||||
@ -539,7 +586,7 @@
|
||||
*
|
||||
* @note The default is @p FALSE.
|
||||
*/
|
||||
#ifndef CH_DBG_FILL_THREADS
|
||||
#if !defined(CH_DBG_FILL_THREADS)
|
||||
#define CH_DBG_FILL_THREADS TRUE
|
||||
#endif
|
||||
|
||||
@ -552,7 +599,7 @@
|
||||
* @note This debug option is not currently compatible with the
|
||||
* tickless mode.
|
||||
*/
|
||||
#ifndef CH_DBG_THREADS_PROFILING
|
||||
#if !defined(CH_DBG_THREADS_PROFILING)
|
||||
#define CH_DBG_THREADS_PROFILING FALSE
|
||||
#endif
|
||||
|
||||
@ -577,7 +624,7 @@
|
||||
* @details User initialization code added to the @p chSysInit() function
|
||||
* just before interrupts are enabled globally.
|
||||
*/
|
||||
#define CH_CFG_SYSTEM_INIT_HOOK(tp) { \
|
||||
#define CH_CFG_SYSTEM_INIT_HOOK() { \
|
||||
/* Add threads initialization code here.*/ \
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user