kernel: remove tickless idle

This feature predated the tickless kernel and has been in legacy mode
for a while. We now have no drivers or systems that do not support
tickless, so remove this option and cleanup the code to only use
tickless.

Signed-off-by: Anas Nashif <anas.nashif@intel.com>
This commit is contained in:
Anas Nashif 2021-03-12 13:13:22 -05:00
commit c076d94eec
17 changed files with 22 additions and 764 deletions

View file

@ -47,34 +47,6 @@ The power management features are classified into the following categories.
* System Power Management
* Device Power Management
Tickless Idle
*************
This is the name used to identify the event-based idling mechanism of the
Zephyr RTOS kernel scheduler. The kernel scheduler can run in two modes. During
normal operation, when at least one thread is active, it sets up the system
timer in periodic mode and runs in an interval-based scheduling mode. The
interval-based mode allows it to time slice between threads. Many times, the
threads would be waiting on semaphores, timeouts or for events. When there
are no threads running, it is inefficient for the kernel scheduler to run
in interval-based mode. This is because, in this mode the timer would trigger
an interrupt at fixed intervals causing the scheduler to be invoked at each
interval. The scheduler checks if any thread is ready to run. If no thread
is ready to run then it is a waste of power because of the unnecessary CPU
processing. This is avoided by the kernel switching to event-based idling
mode whenever there is no thread ready to run.
The kernel holds an ordered list of thread timeouts in the system. These are
the amount of time each thread has requested to wait. When the last active
thread goes to wait, the idle thread is scheduled. The idle thread programs
the timer to one-shot mode and programs the count to the earliest timeout
from the ordered thread timeout list. When the timer expires, a timer event
is generated. The ISR of this event will invoke the scheduler, which would
schedule the thread associated with the timeout. Before scheduling the
thread, the scheduler would switch the timer again to periodic mode. This
method saves power because the CPU is removed from the wait only when there
is a thread ready to run or if an external event occurred.
System Power Management
***********************
@ -90,9 +62,6 @@ such as a SysTick, RTC, counter, or GPIO. Depending on the power mode entered,
only some SoC peripheral modules may be active and can be used as a wake up
source.
Enabling system power management compels the Zephyr kernel scheduler to work in
tickless idle mode (see :option:`CONFIG_TICKLESS_IDLE`).
Power States
============
@ -485,10 +454,6 @@ the following configuration flags.
This flag enables the power management subsystem.
:option:`CONFIG_TICKLESS_IDLE`
This flag enables the tickless idle power saving feature.
:option:`CONFIG_PM_DEVICE`
This flag is enabled if the SOC interface and the devices support device power

View file

@ -189,7 +189,6 @@ config RV32M1_LPTMR_TIMER
bool "RV32M1 LPTMR system timer driver"
default y
depends on SOC_OPENISA_RV32M1_RISCV32
depends on !TICKLESS_IDLE
depends on RV32M1_INTMUX
help
This module implements a kernel device driver for using the LPTMR
@ -199,7 +198,6 @@ config RV32M1_LPTMR_TIMER
config LITEX_TIMER
bool "LiteX Timer"
default y
depends on !TICKLESS_IDLE
depends on SOC_RISCV32_LITEX_VEXRISCV
help
This module implements a kernel device driver for LiteX Timer.

View file

@ -13,12 +13,23 @@
#include "altera_avalon_timer_regs.h"
#include "altera_avalon_timer.h"
#include "legacy_api.h"
/* The old driver "now" API would return a full uptime value. The new
* one only requires the driver to track ticks since the last announce
* call. Implement the new call in terms of the old one on legacy
* drivers by keeping (yet another) uptime value locally.
*/
static uint32_t driver_uptime;
static uint32_t accumulated_cycle_count;
static int32_t _sys_idle_elapsed_ticks = 1;
static void wrapped_announce(int32_t ticks)
{
driver_uptime += ticks;
sys_clock_announce(ticks);
}
static void timer_irq_handler(const void *unused)
{
ARG_UNUSED(unused);
@ -28,7 +39,7 @@ static void timer_irq_handler(const void *unused)
/* Clear the interrupt */
alt_handle_irq((void *)TIMER_0_BASE, TIMER_0_IRQ);
sys_clock_announce(_sys_idle_elapsed_ticks);
wrapped_announce(_sys_idle_elapsed_ticks);
}
int sys_clock_driver_init(const struct device *device)
@ -69,3 +80,8 @@ uint32_t sys_clock_cycle_get_32(void)
*/
return accumulated_cycle_count;
}
uint32_t sys_clock_elapsed(void)
{
return 0;
}

View file

@ -326,7 +326,7 @@ void sys_clock_set_timeout(int32_t ticks, bool idle)
* However for single core using 32-bits arc timer, idle cannot
* be ignored, as 32-bits timer will overflow in a not-long time.
*/
if (IS_ENABLED(CONFIG_TICKLESS_IDLE) && ticks == K_TICKS_FOREVER) {
if (IS_ENABLED(CONFIG_TICKLESS_KERNEL) && ticks == K_TICKS_FOREVER) {
timer0_control_register_set(0);
timer0_count_register_set(0);
timer0_limit_register_set(0);
@ -356,8 +356,7 @@ void sys_clock_set_timeout(int32_t ticks, bool idle)
arch_irq_unlock(key);
#endif
#else
if (IS_ENABLED(CONFIG_TICKLESS_IDLE) && idle
&& ticks == K_TICKS_FOREVER) {
if (IS_ENABLED(CONFIG_TICKLESS_KERNEL) && idle && ticks == K_TICKS_FOREVER) {
timer0_control_register_set(0);
timer0_count_register_set(0);
timer0_limit_register_set(0);

View file

@ -172,8 +172,7 @@ void sys_clock_set_timeout(int32_t ticks, bool idle)
* the counter. (Note: we can assume if idle==true that
* interrupts are already disabled)
*/
if (IS_ENABLED(CONFIG_TICKLESS_IDLE) && idle
&& ticks == K_TICKS_FOREVER) {
if (IS_ENABLED(CONFIG_TICKLESS_KERNEL) && idle && ticks == K_TICKS_FOREVER) {
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
last_load = TIMER_STOPPED;
return;

View file

@ -1,74 +0,0 @@
/*
* Copyright (c) 2018 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_LEGACY_SET_TIME_H__
#define ZEPHYR_LEGACY_SET_TIME_H__
/* Stub implementation of sys_clock_set_timeout() and sys_clock_elapsed()
* in terms of the original APIs. Used by older timer drivers.
* Should be replaced.
*
* Yes, this "header" includes function definitions and must be
* included only once in a single compilation.
*/
#ifdef CONFIG_TICKLESS_IDLE
void z_timer_idle_enter(int32_t ticks);
void clock_idle_exit(void);
#endif
#ifdef CONFIG_TICKLESS_KERNEL
void z_set_time(uint32_t time);
extern uint32_t z_get_program_time(void);
extern uint32_t z_get_remaining_program_time(void);
extern uint32_t z_get_elapsed_program_time(void);
#endif
extern uint64_t clock_uptime(void);
void sys_clock_set_timeout(int32_t ticks, bool idle)
{
#if defined(CONFIG_TICKLESS_IDLE) && defined(CONFIG_TICKLESS_KERNEL)
if (idle) {
z_timer_idle_enter(ticks);
} else {
z_set_time(ticks == K_TICKS_FOREVER ? 0 : ticks);
}
#endif /* TICKLESS_IDLE && TICKLESS_KERNEL */
}
/* The old driver "now" API would return a full uptime value. The new
* one only requires the driver to track ticks since the last announce
* call. Implement the new call in terms of the old one on legacy
* drivers by keeping (yet another) uptime value locally.
*/
static uint32_t driver_uptime;
uint32_t sys_clock_elapsed(void)
{
#ifdef CONFIG_TICKLESS_KERNEL
return (uint32_t)(clock_uptime() - driver_uptime);
#else
return 0;
#endif
}
static void wrapped_announce(int32_t ticks)
{
driver_uptime += ticks;
sys_clock_announce(ticks);
}
#define sys_clock_announce(t) wrapped_announce(t)
#define _sys_clock_always_on (0)
static inline void z_tick_set(int64_t val)
{
/* noop with current kernel code, use sys_clock_announce() */
ARG_UNUSED(val);
}
#endif /* ZEPHYR_LEGACY_SET_TIME_H__ */

View file

@ -112,7 +112,6 @@ typedef struct {
/** @} */
#ifdef CONFIG_TICKLESS_KERNEL
extern int _sys_clock_always_on;
extern void z_enable_sys_clock(void);
#endif

View file

@ -840,17 +840,6 @@ config KERNEL_COHERENCE
endmenu
config TICKLESS_IDLE
# NB: This option is deprecated, see TICKLESS_KERNEL and
# https://github.com/zephyrproject-rtos/zephyr/pull/12234
bool "Tickless idle"
default y if PM || TICKLESS_CAPABLE
help
This option suppresses periodic system clock interrupts whenever the
kernel becomes idle. This permits the system to remain in a power
saving state for extended periods without having to wake up to
service each tick as it occurs.
config TICKLESS_KERNEL
bool "Tickless kernel"
default y if TICKLESS_CAPABLE

View file

@ -11,8 +11,7 @@ config SYS_POWER_MANAGEMENT
This option is deprecated. Please use CONFIG_PM instead.
menuconfig PM
bool "System Power management"
select TICKLESS_IDLE
bool "System Power Management"
depends on SYS_CLOCK_EXISTS && !HAS_NO_SYS_PM
help
This option enables the board to implement extra power management

View file

@ -23,5 +23,3 @@ CONFIG_BT_CTLR_TX_BUFFER_SIZE=60
CONFIG_BT_CTLR_DATA_LENGTH_MAX=60
CONFIG_PM=y
CONFIG_TICKLESS_IDLE=y
CONFIG_TICKLESS_KERNEL=y

View file

@ -1,8 +0,0 @@
# SPDX-License-Identifier: Apache-2.0
cmake_minimum_required(VERSION 3.13.1)
find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE})
project(tickless)
target_sources(app PRIVATE src/main.c)
target_sources_ifdef(CONFIG_ARM app PRIVATE src/timestamps.c)

View file

@ -1,55 +0,0 @@
Title: Tickless Idle Support
Description:
This test verifies the timing accuracy of the tickless idle feature.
The test first calibrates itself by repeatedly sleeping for 10 ticks with the
tickless idle feature disabled. It then repeats this process with the tickless
idle feature enabled. Lastly, it compares the average measured duration of
each approach and displays the result. The tick timing is correct if the
'diff ticks' with tickless enabled matches the SLEEP_TICKS (10) setting in
the source.
The demonstration utilizes microkernel mutex APIs, timers and tickless
idle mode.
--------------------------------------------------------------------------------
Building and Running Project:
This project outputs to the console. It can be built and executed
on QEMU as follows:
make run
--------------------------------------------------------------------------------
Troubleshooting:
Problems caused by out-dated project information can be addressed by
issuing one of the following commands then rebuilding the project:
make clean # discard results of previous builds
# but keep existing configuration info
or
make pristine # discard results of previous builds
# and restore pre-defined configuration info
--------------------------------------------------------------------------------
Sample Output:
Tickless Idle Test
Calibrating TSC...
Calibrated time stamp period = 0x00000000163adc3a
Do the real test with tickless enabled
Going idle for 10 ticks...
start ticks : 343
end ticks : 353
diff ticks : 10
diff time stamp: 0x0000000018a69898
Cal time stamp: 0x00000000163adc3a
variance in time stamp diff: 10 percent
===================================================================
PROJECT EXECUTION SUCCESSFUL

View file

@ -1,5 +0,0 @@
CONFIG_PM=y
CONFIG_ZTEST=y
# The code is written to assume a slow tick rate
CONFIG_SYS_CLOCK_TICKS_PER_SEC=100

View file

@ -1,245 +0,0 @@
/* test_tickless.c - tickless idle tests */
/*
* Copyright (c) 2011, 2013-2014 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
/* DESCRIPTION Unit test for tickless idle feature. */
#include <zephyr.h>
#include <ztest.h>
#include <sys/printk.h>
#include <arch/cpu.h>
#include <tc_util.h>
#if defined(CONFIG_ARCH_POSIX)
#include "posix_board_if.h"
#endif
#define STACKSIZE 4096
#define PRIORITY 6
#define SLEEP_TICKS 10
static struct k_thread thread_tickless;
static K_THREAD_STACK_DEFINE(thread_tickless_stack, STACKSIZE);
#ifdef CONFIG_TICKLESS_IDLE
/* This used to poke an internal kernel variable, which doesn't exit
* any more. It was never documented as an API, and the test never
* failed when it was removed. So just leave it here as a vestigial
* thing until the test gets reworked
*/
int32_t _sys_idle_threshold_ticks;
#endif
#define TICKS_TO_MS (MSEC_PER_SEC / CONFIG_SYS_CLOCK_TICKS_PER_SEC)
/* NOTE: Clock speed may change between platforms */
#define CAL_REPS 16 /* # of loops in timestamp calibration */
/*
* Arch-specific timer resolution/size types, definitions and
* timestamp routines.
*/
#if defined(CONFIG_X86) || defined(CONFIG_ARC) || defined(CONFIG_ARCH_POSIX)
typedef uint64_t _timer_res_t;
#define _TIMER_ZERO 0ULL
/* timestamp routines */
#define _TIMESTAMP_OPEN()
#if defined(CONFIG_ARCH_POSIX)
#define _TIMESTAMP_READ() (posix_get_hw_cycle())
#else
#define _TIMESTAMP_READ() (z_tsc_read())
#endif
#define _TIMESTAMP_CLOSE()
#elif defined(CONFIG_ARM)
# if defined(CONFIG_SOC_TI_LM3S6965_QEMU)
/* A bug in the QEMU ARMv7-M sysTick timer prevents tickless idle support */
#error "This QEMU target does not support tickless idle!"
# endif
typedef uint32_t _timer_res_t;
#define _TIMER_ZERO 0
/* timestamp routines, from timestamps.c */
extern void _timestamp_open(void);
extern uint32_t _timestamp_read(void);
extern void _timestamp_close(void);
#define _TIMESTAMP_OPEN() (_timestamp_open())
#define _TIMESTAMP_READ() (_timestamp_read())
#define _TIMESTAMP_CLOSE() (_timestamp_close())
#else
#error "Unknown target"
#endif
void ticklessTestThread(void)
{
int32_t start_time;
int32_t end_time;
int32_t diff_time;
int32_t diff_ticks;
_timer_res_t start_tsc;
_timer_res_t end_tsc;
_timer_res_t cal_tsc = _TIMER_ZERO;
_timer_res_t diff_tsc = _TIMER_ZERO;
_timer_res_t diff_per;
#ifdef CONFIG_TICKLESS_IDLE
int32_t oldThreshold;
#endif
int i;
printk("Tickless Idle Test\n");
#ifndef CONFIG_TICKLESS_IDLE
printk("WARNING! Tickless idle support has not been enabled!\n");
#endif
printk("Calibrating TSC...\n");
#ifdef CONFIG_TICKLESS_IDLE
oldThreshold = _sys_idle_threshold_ticks;
/* make sure we do not enter tickless idle mode */
_sys_idle_threshold_ticks = 0x7FFFFFFF;
#endif
/* initialize the timer, if necessary */
_TIMESTAMP_OPEN();
for (i = 0; i < CAL_REPS; i++) {
/*
* Do a single tick sleep to get us as close to a tick boundary
* as we can.
*/
k_msleep(TICKS_TO_MS);
start_time = k_uptime_get_32();
start_tsc = _TIMESTAMP_READ();
/* FIXME: one tick less to account for
* one extra tick for _TICK_ALIGN in k_sleep
*/
k_msleep((SLEEP_TICKS - 1) * TICKS_TO_MS);
end_tsc = _TIMESTAMP_READ();
end_time = k_uptime_get_32();
cal_tsc += end_tsc - start_tsc;
}
cal_tsc /= CAL_REPS;
#if defined(CONFIG_X86) || defined(CONFIG_ARC)
printk("Calibrated time stamp period = 0x%x%x\n",
(uint32_t)(cal_tsc >> 32), (uint32_t)(cal_tsc & 0xFFFFFFFFLL));
#elif defined(CONFIG_ARCH_POSIX)
printk("Calibrated time stamp period = %" PRIu64 "\n", cal_tsc);
#elif defined(CONFIG_ARM)
printk("Calibrated time stamp period = 0x%x\n", cal_tsc);
#endif
printk("Do the real test with tickless enabled\n");
#ifdef CONFIG_TICKLESS_IDLE
_sys_idle_threshold_ticks = oldThreshold;
#endif
printk("Going idle for %d ticks...\n", SLEEP_TICKS);
for (i = 0; i < CAL_REPS; i++) {
/*
* Do a single tick sleep to get us as close to a tick boundary
* as we can.
*/
k_msleep(TICKS_TO_MS);
start_time = k_uptime_get_32();
start_tsc = _TIMESTAMP_READ();
/* FIXME: one tick less to account for
* one extra tick for _TICK_ALIGN in k_sleep
*/
k_msleep((SLEEP_TICKS - 1) * TICKS_TO_MS);
end_tsc = _TIMESTAMP_READ();
end_time = k_uptime_get_32();
diff_tsc += end_tsc - start_tsc;
}
diff_tsc /= CAL_REPS;
diff_time = (end_time - start_time);
/* Convert ms to ticks*/
diff_ticks = (diff_time / TICKS_TO_MS);
printk("start time : %d\n", start_time);
printk("end time : %d\n", end_time);
printk("diff time : %d\n", diff_time);
printk("diff ticks : %d\n", diff_ticks);
#if defined(CONFIG_X86) || defined(CONFIG_ARC)
printk("diff time stamp: 0x%x%x\n",
(uint32_t)(diff_tsc >> 32), (uint32_t)(diff_tsc & 0xFFFFFFFFULL));
printk("Cal time stamp: 0x%x%x\n",
(uint32_t)(cal_tsc >> 32), (uint32_t)(cal_tsc & 0xFFFFFFFFLL));
#elif defined(CONFIG_ARCH_POSIX)
printk("diff time stamp: %" PRIu64 "\n", diff_tsc);
printk("Cal time stamp: %" PRIu64 "\n", cal_tsc);
#elif defined(CONFIG_ARM)
printk("diff time stamp: 0x%x\n", diff_tsc);
printk("Cal time stamp: 0x%x\n", cal_tsc);
#endif
/*
* Calculate percentage difference between
* calibrated TSC diff and measured result
*/
if (diff_tsc > cal_tsc) {
diff_per = ((diff_tsc - cal_tsc) * 100U) / cal_tsc;
} else {
diff_per = ((cal_tsc - diff_tsc) * 100U) / cal_tsc;
}
printk("variance in time stamp diff: %d percent\n", (int32_t)diff_per);
zassert_equal(diff_ticks, SLEEP_TICKS,
"* TEST FAILED. TICK COUNT INCORRECT *");
/* release the timer, if necessary */
_TIMESTAMP_CLOSE();
}
/**
* @brief Tests to verify tickless feature
*
* @defgroup kernel_tickless_tests Tickless
* @ingroup all_tests
* @{
*/
/**
* @brief Test to verify tickless functionality
*
* @details Test verifies tickless_idle and tickless
* functionality
*/
void test_tickless(void)
{
k_thread_create(&thread_tickless, thread_tickless_stack,
STACKSIZE,
(k_thread_entry_t) ticklessTestThread,
NULL, NULL, NULL,
PRIORITY, 0, K_NO_WAIT);
k_sleep(K_MSEC(4000));
}
/**
* @}
*/
void test_main(void)
{
ztest_test_suite(tickless,
ztest_unit_test(test_tickless));
ztest_run_test_suite(tickless);
}

View file

@ -1,308 +0,0 @@
/*
* Copyright (c) 2014 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
*
* Timestamp support for tickless idle testing
*
* Platform-specific timestamp support for the tickless idle test.
*/
#include <tc_util.h>
#include <stddef.h>
#include <sys/__assert.h>
#if defined(CONFIG_SOC_TI_LM3S6965_QEMU)
/*
* @brief Use a General Purpose Timer in
* 32-bit periodic timer mode (down-counter)
* (RTC mode's resolution of 1 second is insufficient.)
*/
#define _TIMESTAMP_NUM 0 /* set to timer # for use by timestamp (0-3) */
#define _CLKGATECTRL (*((volatile uint32_t *)0x400FE104))
#define _CLKGATECTRL_TIMESTAMP_EN (1 << (16 + _TIMESTAMP_NUM))
#define _TIMESTAMP_BASE 0x40030000
#define _TIMESTAMP_OFFSET (0x1000 * _TIMESTAMP_NUM)
#define _TIMESTAMP_ADDR (_TIMESTAMP_BASE + _TIMESTAMP_OFFSET)
#define _TIMESTAMP_CFG (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0)))
#define _TIMESTAMP_CTRL (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0xC)))
#define _TIMESTAMP_MODE (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x4)))
#define _TIMESTAMP_LOAD (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x28)))
#define _TIMESTAMP_IMASK (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x18)))
#define _TIMESTAMP_ISTATUS (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x1C)))
#define _TIMESTAMP_ICLEAR (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x24)))
#define _TIMESTAMP_VAL (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x48)))
/*
* Set the rollover value such that it leaves the most significant bit of
* the returned timestamp value unused. This allows room for extended values
* when handling rollovers when converting to an up-counter value.
*/
#define _TIMESTAMP_MAX ((uint32_t)0x7FFFFFFF)
#define _TIMESTAMP_EXT ((uint32_t)0x80000000)
/**
*
* @brief Timestamp initialization
*
* This routine initializes the timestamp timer.
*
* @return N/A
*/
void _timestamp_open(void)
{
/* QEMU does not currently support the 32-bit timer modes of the GPTM */
printk("WARNING! Timestamp is not supported for this target!\n");
/* enable timer access */
_CLKGATECTRL |= _CLKGATECTRL_TIMESTAMP_EN;
/* minimum 3 clk delay is required before timer register access */
k_sleep(K_TICKS(3));
_TIMESTAMP_CTRL = 0x0; /* disable/reset timer */
_TIMESTAMP_CFG = 0x0; /* 32-bit timer */
_TIMESTAMP_MODE = 0x2; /* periodic mode */
/* maximum interval to reduce rollovers */
_TIMESTAMP_LOAD = _TIMESTAMP_MAX;
_TIMESTAMP_IMASK = 0x70F; /* mask all timer interrupts */
_TIMESTAMP_ICLEAR = 0x70F; /* clear all interrupt status */
_TIMESTAMP_CTRL = 0x1; /* enable timer */
}
/**
*
* @brief Timestamp timer read
*
* This routine returns the timestamp value.
*
* @return timestamp value
*/
uint32_t _timestamp_read(void)
{
static uint32_t last_timer_val;
static uint32_t cnt;
uint32_t timer_val = _TIMESTAMP_VAL;
/* handle rollover for every other read (end of sleep) */
if ((cnt % 2) && (timer_val > last_timer_val)) {
last_timer_val = timer_val;
/* convert to extended up-counter value */
timer_val = _TIMESTAMP_EXT + (_TIMESTAMP_MAX - timer_val);
} else {
last_timer_val = timer_val;
/* convert to up-counter value */
timer_val = _TIMESTAMP_MAX - timer_val;
}
cnt++;
return timer_val;
}
/**
*
* @brief Timestamp release
*
* This routine releases the timestamp timer.
*
* @return N/A
*/
void _timestamp_close(void)
{
/* disable/reset timer */
_TIMESTAMP_CTRL = 0x0;
_TIMESTAMP_CFG = 0x0;
/* disable timer access */
_CLKGATECTRL &= ~_CLKGATECTRL_TIMESTAMP_EN;
}
#elif defined(CONFIG_SOC_MK64F12)
/* Freescale FRDM-K64F target - use RTC (prescale value) */
#define _COUNTDOWN_TIMER false
#define _CLKGATECTRL (*((volatile uint32_t *)0x4004803C))
#define _CLKGATECTRL_TIMESTAMP_EN (1 << 29)
#define _SYSOPTCTRL2 (*((volatile uint32_t *)0x40048004))
#define _SYSOPTCTRL2_32KHZRTCCLK (1 << 4)
#define _TIMESTAMP_ADDR (0x4003D000)
#define _TIMESTAMP_ICLEAR (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x24)))
#define _TIMESTAMP_VAL (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0)))
#define _TIMESTAMP_PRESCALE (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x4)))
#define _TIMESTAMP_COMP (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0xC)))
#define _TIMESTAMP_CTRL (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x10)))
#define _TIMESTAMP_STATUS (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x14)))
#define _TIMESTAMP_LOCK (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x18)))
#define _TIMESTAMP_IMASK (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x1C)))
#define _TIMESTAMP_RACCESS (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x800)))
#define _TIMESTAMP_WACCESS (*((volatile uint32_t *)(_TIMESTAMP_ADDR + 0x804)))
/**
*
* @brief Timestamp initialization
*
* This routine initializes the timestamp timer.
*
* @return N/A
*/
void _timestamp_open(void)
{
/* enable timer access */
_CLKGATECTRL |= _CLKGATECTRL_TIMESTAMP_EN;
/* set 32 KHz RTC clk */
_SYSOPTCTRL2 |= _SYSOPTCTRL2_32KHZRTCCLK;
_TIMESTAMP_STATUS = 0x0; /* disable counter */
_TIMESTAMP_CTRL = 0x100; /* enable oscillator */
_TIMESTAMP_LOCK = 0xFF; /* unlock registers */
_TIMESTAMP_PRESCALE = 0x0; /* reset prescale value */
_TIMESTAMP_COMP = 0x0; /* reset compensation values */
_TIMESTAMP_RACCESS = 0xFF; /* allow register read access */
_TIMESTAMP_WACCESS = 0xFF; /* allow register write access */
_TIMESTAMP_IMASK = 0x0; /* mask all timer interrupts */
/* minimum 0.3 sec delay required for oscillator stabilization */
k_msleep(0.3 * MSEC_PER_SEC);
/* clear invalid time flag in status register */
_TIMESTAMP_VAL = 0x0;
_TIMESTAMP_STATUS = 0x10; /* enable counter */
}
/**
*
* @brief Timestamp timer read
*
* This routine returns the timestamp value.
*
* @return timestamp value
*/
uint32_t _timestamp_read(void)
{
static uint32_t last_prescale;
static uint32_t cnt;
uint32_t prescale1 = _TIMESTAMP_PRESCALE;
uint32_t prescale2 = _TIMESTAMP_PRESCALE;
/* ensure a valid reading */
while (prescale1 != prescale2) {
prescale1 = _TIMESTAMP_PRESCALE;
prescale2 = _TIMESTAMP_PRESCALE;
}
/* handle prescale rollover @ 0x8000
* for every other read (end of sleep)
*/
if ((cnt % 2) && (prescale1 < last_prescale)) {
prescale1 += 0x8000;
}
last_prescale = prescale2;
cnt++;
return prescale1;
}
/**
*
* @brief Timestamp release
*
* This routine releases the timestamp timer.
*
* @return N/A
*/
void _timestamp_close(void)
{
_TIMESTAMP_STATUS = 0x0; /* disable counter */
_TIMESTAMP_CTRL = 0x0; /* disable oscillator */
}
#elif defined(CONFIG_SOC_FAMILY_SAM)
/* Atmel SAM family processor - use RTT (Real-time Timer) */
#include <soc.h>
/**
*
* @brief Timestamp initialization
*
* This routine initializes the timestamp timer.
*
* @return N/A
*/
void _timestamp_open(void)
{
/* enable RTT clock from PMC */
soc_pmc_peripheral_enable(ID_RTT);
/* Reset RTT and set prescaler to 3, minimum required by SAM E70 SoC */
RTT->RTT_MR = RTT_MR_RTTRST | RTT_MR_RTPRES(3);
}
/**
*
* @brief Timestamp timer read
*
* This routine returns the timestamp value.
*
* @return timestamp value
*/
uint32_t _timestamp_read(void)
{
uint32_t timer_val_0;
uint32_t timer_val_1;
/* As RTT_VR can be updated asynchronously with the Master Clock, it
* must be read twice at the same value to ensure the read value is
* correct.
*/
do {
timer_val_0 = RTT->RTT_VR;
timer_val_1 = RTT->RTT_VR;
} while (timer_val_0 != timer_val_1);
return timer_val_0;
}
/**
*
* @brief Timestamp release
*
* This routine releases the timestamp timer.
*
* @return N/A
*/
void _timestamp_close(void)
{
/* disable RTT clock from PMC */
soc_pmc_peripheral_disable(ID_RTT);
}
#else
#error "Unknown platform"
#endif /* CONFIG_SOC_xxx */

View file

@ -1,6 +0,0 @@
tests:
kernel.tickless:
arch_exclude: nios2 riscv32
filter: CONFIG_X86 or (CONFIG_ARM and (CONFIG_SOC_MK64F12
or CONFIG_SOC_SERIES_SAM3X)) or CONFIG_ARCH_POSIX
tags: tickless kernel

View file

@ -2,9 +2,6 @@ tests:
subsys.power.device_pm:
# arch_irq_unlock(0) can't work correctly on these arch
arch_exclude: arc xtensa
# When CONFIG_TICKLESS_IDLE enable, some of these platforms don't
# provide a timer driver. Other platforms are excluded because
# they lack some other required feature.
platform_exclude: rv32m1_vega_ri5cy rv32m1_vega_zero_riscy litex_vexriscv
nrf5340dk_nrf5340_cpunet
integration_platforms: