1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

Merge pull request #18260 from gschorcht/cpu/esp32/add_riscv_platform_code

cpu/esp32: add platform code for RISC-V based ESP32x SoCs
This commit is contained in:
benpicco 2022-07-18 17:43:02 +02:00 committed by GitHub
commit e1bc1767af
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 435 additions and 10 deletions

View File

@ -141,7 +141,7 @@ void ets_timer_done(ETSTimer *ptimer)
void ets_timer_arm_us(ETSTimer *timer, uint32_t tmout, bool repeat)
{
DEBUG("%s timer=%p tmout=%u repeat=%d\n", __func__, timer, tmout, repeat);
DEBUG("%s timer=%p tmout=%"PRIu32" repeat=%d\n", __func__, timer, tmout, repeat);
struct _ets_to_ztimer* e2xt = _ets_to_ztimer_get(timer);

View File

@ -1,5 +1,5 @@
/*
* Copyright (C) 2020 Gunar Schorcht
* Copyright (C) 2022 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
@ -82,7 +82,8 @@ void rtt_init(void)
}
}
DEBUG("%s rtt_offset=%u @rtc=%llu rtc_active=%d @sys_time=%llu\n", __func__,
DEBUG("%s rtt_offset=%" PRIu32 " @rtc=%" PRIu64
" rtc_active=%d @sys_time=%" PRIi64 "\n", __func__,
_rtt_offset, _rtc_get_counter(),
(_rtt_hw == &_rtt_hw_sys_driver) ? 1 : 0, system_get_time_64());
@ -132,7 +133,8 @@ uint32_t rtt_get_counter(void)
{
/* we use only the lower 32 bit of the 48-bit RTC counter */
uint32_t counter = _rtt_hw->get_counter() + _rtt_offset;
DEBUG("%s counter=%u @sys_time=%u\n", __func__, counter, system_get_time());
DEBUG("%s counter=%" PRIu32 " @sys_time=%" PRIu32" \n",
__func__, counter, system_get_time());
return counter;
}
@ -141,7 +143,7 @@ void rtt_set_counter(uint32_t counter)
uint32_t _rtt_current = _rtt_hw->get_counter();
_rtt_offset = counter - _rtt_current;
DEBUG("%s set=%u rtt_offset=%u @rtt=%u\n",
DEBUG("%s set=%" PRIu32 " rtt_offset=%" PRIu32 " @rtt=%" PRIu32 "\n",
__func__, counter, _rtt_offset, _rtt_current);
_rtt_update_hw_alarm();
@ -154,7 +156,7 @@ void rtt_set_alarm(uint32_t alarm, rtt_cb_t cb, void *arg)
rtt_counter.alarm_cb = cb;
rtt_counter.alarm_arg = arg;
DEBUG("%s alarm=%u @rtt=%u\n", __func__, alarm, counter);
DEBUG("%s alarm=%" PRIu32 " @rtt=%" PRIu32 "\n", __func__, alarm, counter);
_rtt_update_hw_alarm();
}
@ -166,7 +168,7 @@ void rtt_clear_alarm(void)
rtt_counter.alarm_cb = NULL;
rtt_counter.alarm_arg = NULL;
DEBUG("%s @rtt=%u\n", __func__, (uint32_t)_rtt_hw->get_counter());
DEBUG("%s @rtt=%" PRIu32 "\n", __func__, (uint32_t)_rtt_hw->get_counter());
_rtt_update_hw_alarm();
}
@ -197,7 +199,7 @@ uint64_t rtt_pm_sleep_enter(unsigned mode)
uint32_t counter = rtt_get_counter();
uint64_t t_diff = RTT_TICKS_TO_US(rtt_counter.alarm_active - counter);
DEBUG("%s rtt_alarm=%u @rtt=%u t_diff=%llu\n", __func__,
DEBUG("%s rtt_alarm=%" PRIu32 " @rtt=%" PRIu32 " t_diff=%llu\n", __func__,
rtt_counter.alarm_active, counter, t_diff);
if (t_diff) {
@ -250,7 +252,7 @@ static void IRAM_ATTR _rtt_isr(void *arg)
if (rtt_counter.wakeup) {
rtt_counter.wakeup = false;
DEBUG("%s wakeup alarm alarm=%u rtt_alarm=%u @rtt=%u\n",
DEBUG("%s wakeup alarm alarm=%" PRIu32 " rtt_alarm=%" PRIu32 " @rtt=%" PRIu32 "\n",
__func__, alarm, rtt_counter.alarm_active, rtt_get_counter());
}
@ -276,7 +278,7 @@ static void IRAM_ATTR _rtt_isr(void *arg)
}
}
DEBUG("%s next rtt=%u\n", __func__, rtt_counter.alarm_active);
DEBUG("%s next rtt=%" PRIu32 "\n", __func__, rtt_counter.alarm_active);
}
uint32_t _rtt_hw_to_rtt_counter(uint32_t hw_counter)

View File

@ -69,6 +69,11 @@ config HAS_ARCH_ESP_XTENSA
help
Indicates that an Xtensa-based 'ESP' architecture is being used.
config HAS_ARCH_ESP_RISCV
bool
help
Indicates that an RISC-V-based 'ESP' architecture is being used.
config HAS_ESP_WIFI_ENTERPRISE
bool
help
@ -119,6 +124,7 @@ config MODULE_ESP_LOG_STARTUP
config MODULE_ESP_QEMU
bool "Simulate ESP with QEMU"
rsource "esp-riscv/Kconfig"
rsource "esp-xtensa/Kconfig"
rsource "freertos/Kconfig"
rsource "periph/Kconfig"

View File

@ -21,4 +21,8 @@ ifneq (,$(filter esp_xtensa,$(USEMODULE)))
DIRS += esp-xtensa
endif
ifneq (,$(filter esp_riscv,$(USEMODULE)))
DIRS += esp-riscv
endif
include $(RIOTBASE)/Makefile.base

View File

@ -25,6 +25,10 @@ ifeq (xtensa,$(CPU_ARCH))
USEMODULE += xtensa
endif
ifeq (riscv_esp32,$(CPU_ARCH))
USEMODULE += esp_riscv
endif
# Features used by ESP*
FEATURES_REQUIRED += newlib

View File

@ -26,6 +26,10 @@ ifeq (xtensa,$(CPU_ARCH))
FEATURES_PROVIDED += arch_esp_xtensa
endif
ifeq (riscv_esp32,$(CPU_ARCH))
FEATURES_PROVIDED += arch_esp_riscv
endif
FEATURES_CONFLICT += esp_wifi_ap:esp_now
FEATURES_CONFLICT_MSG += "ESP_NOW and ESP_WIFI_AP can not be used at the same time."

View File

@ -0,0 +1,14 @@
# Copyright (c) 2022 Gunar Schorcht
#
# This file is subject to the terms and conditions of the GNU Lesser
# General Public License v2.1. See the file LICENSE in the top level
# directory for more details.
#
config MODULE_ESP_RISCV
bool
depends on TEST_KCONFIG
depends on HAS_ARCH_ESP_RISCV
default y
help
Platform-dependent code for Xtensa-based ESP SoCs.

View File

@ -0,0 +1,3 @@
MODULE=esp_riscv
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,75 @@
/*
* Copyright (C) 2022 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_esp_common
* @{
*
* @file
* @brief Exception handling for RISC-V-based ESP SoCs
*
* @author Gunar Schorcht <gunar@schorcht.net>
* @}
*/
#include <inttypes.h>
#include "kernel_defines.h"
#include "panic.h"
#include "periph/pm.h"
#include "esp_attr.h"
#include "riscv/rvruntime-frames.h"
#include "rom/ets_sys.h"
static const char *exceptions[] = {
"nil",
"0x1: PMP Instruction access fault",
"0x2: Illegal Instruction",
"0x3: Hardware Breakpoint/Watchpoint or EBREAK",
"nil",
"0x5: PMP Load access fault",
"nil",
"0x7: PMP Store access fault",
"0x8: ECALL from U mode",
"nil",
"nil",
"0xb: ECALL from M mode",
};
static RvExcFrame *_frame = NULL;
void init_exceptions (void)
{
}
void IRAM_ATTR xt_unhandled_exception(RvExcFrame *frame)
{
_frame = frame;
core_panic(PANIC_GENERAL_ERROR, "Unhandled exception");
}
void IRAM_ATTR panicHandler(RvExcFrame *frame)
{
_frame = frame;
core_panic(PANIC_GENERAL_ERROR, "Panic handler");
}
extern void heap_stats(void);
void panic_arch(void)
{
if (_frame) {
/* TODO */
ets_printf("Exception @0x%08"PRIx32", cause %s\n",
_frame->mepc, exceptions[_frame->mcause]);
}
#if defined(DEVELHELP)
heap_stats();
#endif
}

View File

@ -0,0 +1,97 @@
/*
* Copyright (C) 2022 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_esp32
* @{
*
* @file
* @brief Implementation of the kernels irq interface
*
* @author Gunar Schorcht <gunar@schorcht.net>
*
* @}
*/
#include "irq_arch.h"
#include "esp_attr.h"
#include "hal/interrupt_controller_types.h"
#include "hal/interrupt_controller_ll.h"
#include "soc/periph_defs.h"
#define ENABLE_DEBUG 0
#include "debug.h"
#define RVHAL_EXCM_LEVEL 4
/**
* @brief Disable all maskable interrupts
*/
unsigned int IRAM_ATTR irq_disable(void)
{
uint32_t mstatus;
/* clear MIE bit in register mstatus */
__asm__ volatile ("csrrc %0, mstatus, %1" : "=r"(mstatus) : "rK"(MSTATUS_MIE) : "memory");
/* save interrupt priority level threshold */
uint32_t state = *((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG);
/* set interrupt priority level threshold to exception level */
*((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG) = RVHAL_EXCM_LEVEL;
/* set MIE bit in register mstatus */
__asm__ volatile ("csrrs %0, mstatus, %1" : "=r"(mstatus) : "rK"(MSTATUS_MIE) : "memory");
DEBUG("%s %02x(%02x)\n", __func__, RVHAL_EXCM_LEVEL, (unsigned)state);
return state;
}
/**
* @brief Enable all maskable interrupts
*/
unsigned int IRAM_ATTR irq_enable(void)
{
uint32_t state = *((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG);
/* set interrupt priority level threshold to 0 */
*((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG) = 0;
/* small delay needed here */
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
DEBUG("%s %02x(%02x)\n", __func__, 0, (unsigned)state);
return state;
}
/**
* @brief Restore the state of the IRQ flags
*/
void IRAM_ATTR irq_restore(unsigned int state)
{
uint32_t old = *((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG);
/* set interrupt priority level threshold to old level */
*((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG) = state;
/* small delay needed here */
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
DEBUG("%s %02x(%02x)\n", __func__, (unsigned)state, (unsigned)old);
}
/**
* @brief Test if IRQs are currently enabled
*/
bool IRAM_ATTR irq_is_enabled(void)
{
return *((volatile uint32_t *)INTERRUPT_CORE0_CPU_INT_THRESH_REG) == 0;
}

View File

@ -0,0 +1,216 @@
/*
* Copyright (C) 2022 Gunar Schorcht
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_esp_common
* @{
*
* @file
* @brief Implementation of kernel's architecture dependent interface
*
* This file implements kernel's architecture dependent interface for RISC-V
* based ESP32x SoCs
*
* @note The implementation in `$(RIOTCPU)/risc_common/thread_arch.c` cannot
* be used because
* - it requires some modifications for compatibility with ESP-IDF code
* - the ESP-IDF uses a different context frame
*
* @author Gunar Schorcht <gunar@schorcht.net>
*
* @}
*/
#include <string.h>
#include "esp_attr.h"
#include "irq.h"
#include "thread.h"
#include "sched.h"
#include "syscalls.h"
#include "freertos/FreeRTOS.h"
#include "riscv/rvruntime-frames.h"
#include "soc/soc.h"
#include "soc/system_reg.h"
/*
* The FreeRTOS implementation for interrupt/exception handling of ESP-IDF,
* which is also used for RIOT to ensure compatibility with other ESP-IDF code,
* uses a separate stack in the interrupt context. Therefore, the stack and
* a pointer to the top of this stack are defined here.
*
* For compatibility reasons with xtensa implementation, we call them
* port_IntStack and port_IntStackTop.
*/
/* bottom and top of ISR stack */
extern uint8_t port_IntStack;
extern uint8_t port_IntStackTop;
/* pointer the top of the ISR stack as required by ESP-IDF */
uint8_t *xIsrStackTop = &port_IntStackTop;
/* context frame as used by the ESP-IDF */
typedef struct context_switch_frame {
uint32_t mepc; /**< machine exception program counter instead of x0 */
uint32_t ra; /**< x1 - return address (caller saved) */
uint32_t gp; /**< x3 - global pointer (-) */
uint32_t sp; /**< x2 - stack pointer (callee saved) */
uint32_t tp; /**< x4 - thread pointer (-) */
uint32_t t0; /**< x5 - temporary register (caller saved) */
uint32_t t1; /**< x6 - temporary register (caller saved) */
uint32_t t2; /**< x7 - temporary register (caller saved) */
uint32_t s0; /**< x8 - saved register / frame pointer (callee saved) */
uint32_t s1; /**< x9 - saved register (callee saved) */
uint32_t a0; /**< x10 - function argument / return value (caller saved) */
uint32_t a1; /**< x11 - function argument / return value (caller saved) */
uint32_t a2; /**< x12 - function argument (caller saved) */
uint32_t a3; /**< x13 - function argument (caller saved) */
uint32_t a4; /**< x14 - function argument (caller saved) */
uint32_t a5; /**< x15 - function argument (caller saved) */
uint32_t a6; /**< x16 - function argument (caller saved) */
uint32_t a7; /**< x17 - function argument (caller saved) */
uint32_t s2; /**< x18 - saved register (callee saved) */
uint32_t s3; /**< x19 - saved register (callee saved) */
uint32_t s4; /**< x20 - saved register (callee saved) */
uint32_t s5; /**< x21 - saved register (callee saved) */
uint32_t s6; /**< x22 - saved register (callee saved) */
uint32_t s7; /**< x23 - saved register (callee saved) */
uint32_t s8; /**< x24 - saved register (callee saved) */
uint32_t s9; /**< x25 - saved register (callee saved) */
uint32_t s10; /**< x26 - saved register (callee saved) */
uint32_t s11; /**< x27 - saved register (callee saved) */
uint32_t t3; /**< x28 - temporary register (caller saved) */
uint32_t t4; /**< x29 - temporary register (caller saved) */
uint32_t t5; /**< x30 - temporary register (caller saved) */
uint32_t t6; /**< x31 - temporary register (caller saved) */
} context_switch_frame_t;
/*
* The following function is a modified copy of function `thread_stack_init`
* in `$(RIOTCPU)/risc_common/thread_arch.c`, which is under the following
* copyright:
*
* Copyright (C) 2017, 2019 Ken Rabold, JP Bonn
*
* Modifications:
* - For compatibility with ESP-IDF, the context frame is defined as
* used by the ESP-IDF.
* - The `STACK_MARKER` is not used to identify the top of the stack.
* Instead, the stack is initialized in the `thread_create` function in
* `$(RIOTBASE)/core/thread.c` as expected in the `thread_measure_stack_free`
* function.
* - Support for `__global_pointer$` and TLS has been added.
*/
char* thread_stack_init(thread_task_func_t task_func, void *arg, void *stack_start, int stack_size)
{
_Static_assert(sizeof(context_switch_frame_t) == 32 * sizeof(uint32_t),
"context frame has to store 32 registers");
context_switch_frame_t *sf;
uint8_t *stk_top;
/* calculate the top of the stack */
stk_top = (uint8_t *)stack_start + stack_size;
/* per ABI align stack pointer to 16 byte boundary. */
stk_top = (uint8_t *)((uintptr_t)stk_top & ~((uintptr_t)0xf));
/* prepare thread local storage and the thread pointer */
extern uint32_t __global_pointer$;
#if !defined(RISCV_NO_RELAX)
extern char _thread_local_start, _thread_local_end, _flash_rodata_start;
uint8_t *_local_start;
uint32_t _local_size = (uint32_t)(&_thread_local_end - &_thread_local_start);
_local_size = ALIGNUP(0x10, _local_size);
stk_top -= _local_size;
_local_start = stk_top;
memcpy(_local_start, &_thread_local_start, _local_size);
uint8_t *tp;
tp = _local_start - (&_thread_local_start - &_flash_rodata_start);
#else
uint8_t *tp = NULL;
#endif
/* reserve space for the stack frame. */
stk_top = stk_top - sizeof(*sf);
/* populate the stack frame with default values for starting the thread. */
sf = (struct context_switch_frame *)((uintptr_t)stk_top);
/* Clear stack frame */
memset(sf, 0, sizeof(*sf));
/* set initial reg values */
sf->mepc = (uint32_t)task_func;
sf->a0 = (uint32_t)arg;
sf->gp = (uint32_t)__global_pointer$;
sf->tp = (uint32_t)tp;
/* if the thread exits go to sched_task_exit() */
sf->ra = (uint32_t)sched_task_exit;
return (char *)stk_top;
}
void IRAM_ATTR thread_yield_isr(void* arg)
{
(void)arg;
/**
* Context switches are realized using software interrupts since interrupt
* entry and exit functions are used save and restore complete
* context.
*/
/* clear the interrupt first */
WRITE_PERI_REG(SYSTEM_CPU_INTR_FROM_CPU_0_REG, 0);
/* set the context switch flag (indicates that context has to be switched
is switch on exit from interrupt in rtos_int_exit */
sched_context_switch_request = 1;
}
void IRAM_ATTR thread_yield_higher(void)
{
/* reset hardware watchdog */
system_wdt_feed();
/**
* If we are already in an interrupt handler, the function simply sets the
* context switch flag, which indicates that the context has to be switched
* in the rtos_int_exit function when exiting the interrupt. Otherwise, we
* will generate a software interrupt to force the context switch when
* exiting from the software interrupt (see thread_yield_isr).
*/
if (irq_is_in()) {
/* if already in ISR, only set the sched_context_switch_request flag */
sched_context_switch_request = 1;
}
else {
/* otherwise trigger a software interrupt for context switch */
WRITE_PERI_REG(SYSTEM_CPU_INTR_FROM_CPU_0_REG, 1);
/* small delay of 3-4 instructions required here before we return */
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
__asm__ volatile ( "nop" );
}
}
NORETURN void cpu_switch_context_exit(void)
{
/* enable interrupts */
irq_enable();
/* force a context switch to another thread */
thread_yield_higher();
UNREACHABLE();
}