Update some compilation issues

This commit is contained in:
Gregory Nutt 2016-10-30 15:38:51 -06:00
parent a4c3fef0b7
commit 85ed3dae9a
12 changed files with 192 additions and 27 deletions

View File

@ -322,7 +322,7 @@
#define NR_IRQS (XTENSA_NIRQ_INTERNAL+ESP32_NIRQ_PERIPH+ESP32_NIRQ_GPIO)
/* CPU Interrupts.
/* Xtensa CPU Interrupts.
*
* Each of the two CPUs (PRO and APP) have 32 interrupts each, of which
* 26 can be mapped to peripheral interrupts:

View File

@ -110,28 +110,31 @@
/* In the XTENSA model, the state is copied from the stack to the TCB, but
* only a referenced is passed to get the state from the TCB.
*
* REVISIT: It would not be too difficult to save only a pointer to the
* state save area in the TCB and thus avoid the copy.
*/
#define xtensa_savestate(regs) xtensa_copystate(regs, (uint32_t*)CURRENT_REGS)
#define xtensa_restorestate(regs) do { CURRENT_REGS = regs; } while (0)
/* Interrupt codes from other CPUs: */
#define CPU_INTCODE_PAUSE 0
/* Register access macros */
# define getreg8(a) (*(volatile uint8_t *)(a))
# define putreg8(v,a) (*(volatile uint8_t *)(a) = (v))
# define getreg16(a) (*(volatile uint16_t *)(a))
# define putreg16(v,a) (*(volatile uint16_t *)(a) = (v))
# define getreg32(a) (*(volatile uint32_t *)(a))
# define putreg32(v,a) (*(volatile uint32_t *)(a) = (v))
#define getreg8(a) (*(volatile uint8_t *)(a))
#define putreg8(v,a) (*(volatile uint8_t *)(a) = (v))
#define getreg16(a) (*(volatile uint16_t *)(a))
#define putreg16(v,a) (*(volatile uint16_t *)(a) = (v))
#define getreg32(a) (*(volatile uint32_t *)(a))
#define putreg32(v,a) (*(volatile uint32_t *)(a) = (v))
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
typedef void (*xtensa_vector_t)(void);
#endif
/****************************************************************************
* Public Data
****************************************************************************/
@ -253,7 +256,10 @@ void xtensa_panic(int xptcode, uint32_t *regs) noreturn_function;
/* Software interrupt handler */
int xtensa_swint(int irq, FAR void *context);
#ifdef CONFIG_SMP
int xtensa_cpu_interrupt(int cpu, int intcode);
void xtensa_pause_handler(void);
#endif
/* Synchronous context switching */

View File

@ -256,9 +256,9 @@ xtensa_coproc_savestate:
/* Restore a13-15 and return */
132i a13, sp, LOCAL_OFFSET(1)
132i a14, sp, LOCAL_OFFSET(2)
132i a15, sp, LOCAL_OFFSET(3)
l32i a13, sp, LOCAL_OFFSET(1)
l32i a14, sp, LOCAL_OFFSET(2)
l32i a15, sp, LOCAL_OFFSET(3)
RET(16)
@ -443,9 +443,9 @@ xtensa_coproc_restorestate:
/* Restore a13-15 and return */
132i a13, sp, LOCAL_OFFSET(1)
132i a14, sp, LOCAL_OFFSET(2)
132i a15, sp, LOCAL_OFFSET(3)
l32i a13, sp, LOCAL_OFFSET(1)
l32i a14, sp, LOCAL_OFFSET(2)
l32i a15, sp, LOCAL_OFFSET(3)
RET(16)

View File

@ -68,7 +68,13 @@
static inline uint32_t xtensa_getsp(void)
{
register uint32_t sp;
#warning Missing logic
__asm__ __volatile__
(
"mov %0, sp\n"
: "=r" (sp)
);
return sp;
}

View File

@ -284,7 +284,7 @@ _xtensa_level1_handler:
/* Restore only level-specific regs (the rest were already restored) */
l32i a0, sp, (4 * REG_PS) /* Retrieve interruptee's PS */
wsr a0, EPS_1
wsr a0, PS
l32i a0, sp, (4 * REG_PC) /* Retrieve interruptee's PC */
wsr a0, EPC_1
l32i a0, sp, (4 * REG_A0) /* Retrieve interruptee's A0 */

View File

@ -86,7 +86,7 @@ uint32_t *xtensa_irq_dispatch(int irq, uint32_t *regs)
irq_dispatch(irq, regs);
#if defined(CONFIG_ARCH_FPU) || defined(CONFIG_ARCH_ADDRENV)
#if XCHAL_CP_NUM > 0 || defined(CONFIG_ARCH_ADDRENV)
/* Check for a context switch. If a context switch occurred, then
* CURRENT_REGS will have a different value than it did on entry.
*/

View File

@ -38,6 +38,7 @@
#include <nuttx/config.h>
#include <arch/irq.h>
#include <arch/chip/core-isa.h>
#include <arch/xtensa/xtensa_specregs.h>
@ -272,7 +273,7 @@ _double_exception_vector:
mov a0, sp /* sp == a1 */
addi sp, sp, -(4 * XCPTCONTEXT_SIZE) /* Allocate interrupt stack frame */
s32i a0, sp, (4 * REG_A1) /* Save pre-interrupt SP */
rsr a0, EPS_1 /* Save interruptee's PS -- REVISIT */
rsr a0, EPS /* Save interruptee's PS -- REVISIT */
s32i a0, sp, (4 * REG_PS)
rsr a0, DEPC /* Save interruptee's PC */
s32i a0, sp, (4 * REG_PC)
@ -309,7 +310,7 @@ _kernel_exception_vector:
mov a0, sp /* sp == a1 */
addi sp, sp, -(4 * XCPTCONTEXT_SIZE) /* Allocate interrupt stack frame */
s32i a0, sp, (4 * REG_A1) /* Save pre-interrupt SP */
rsr a0, EPS_1 /* Save interruptee's PS */
rsr a0, EPS /* Save interruptee's PS */
s32i a0, sp, (4 * REG_PS)
rsr a0, EPC_1 /* Save interruptee's PC */
s32i a0, sp, (4 * REG_PC)

View File

@ -63,6 +63,10 @@ ifeq ($(CONFIG_SPINLOCK),y)
CMN_CSRCS += xtensa_testset.c
endif
ifeq ($(CONFIG_SMP),y)
CMN_CSRCS += xtensa_cpu_pause.c
endif
# Use of common/xtensa_etherstub.c is deprecated. The preferred mechanism
# is to use CONFIG_NETDEV_LATEINIT=y to suppress the call to
# up_netinitialize() in xtensa_initialize.c. Then this stub would not be
@ -85,8 +89,8 @@ CHIP_CSRCS += esp32_start.c esp32_timerisr.c
ifeq ($(CONFIG_SMP),y)
CHIP_ASRCS = esp32_cpuindex.S
#CMN_CSRCS += esp32_cpustart.c esp32_cpupause.c esp32_cpuidlestack.c
CMN_CSRCS += esp32_cpustart.c
CMN_CSRCS += esp32_cpustart.c esp32_cpu_interrupt.c
#CMN_CSRCS += esp32_cpuidlestack.c
endif
ifeq ($(CONFIG_ESP32_UART),y)

View File

@ -0,0 +1,87 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_cpu_interrupt.c
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <arch/irq.h>
#include "xtensa.h"
#ifdef CONFIG_SMP
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Name: esp32_cpu_interrupt
*
* Description:
* Called to handle the CPU0-4 interrupts.
*
****************************************************************************/
int esp32_cpu_interrupt(int irq, FAR void *context)
{
uint32_t *regs = (uint32_t *)context;
int intcode;
DEBUGASSERT(regs != NULL);
intcode = regs[REG_A2];
/* Dispatch the inter-CPU interrupt based on the intcode value */
switch (intcode)
{
case CPU_INTCODE_PAUSE:
xtensa_pause_handler();
break;
default:
DEBUGPANIC();
break;
}
return OK;
}
#endif /* CONFIG_SMP */

View File

@ -0,0 +1,62 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_cpu_interrupt.h
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_ESP32_CPU_INTERRUPT_H
#define __ARCH_XTENSA_SRC_ESP32_ESP32_CPU_INTERRUPT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#ifdef CONFIG_SMP
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Name: esp32_cpu_interrupt
*
* Description:
* Called to handle the CPU0-4 interrupts.
*
****************************************************************************/
int esp32_cpu_interrupt(int irq, FAR void *context);
#endif /* CONFIG_SMP */
#endif /* __ARCH_XTENSA_SRC_ESP32_ESP32_CPU_INTERRUPT_H */

View File

@ -75,7 +75,6 @@ CONFIG_ARCH_CHIP="esp32"
# CONFIG_SERIAL_TERMIOS is not set
CONFIG_ARCH_CHIP_ESP32=y
CONFIG_ARCH_FAMILY_LX6=y
CONFIG_XTENSA_CALL0_ABI=y
# CONFIG_XTENSA_USE_OVLY is not set
CONFIG_XTENSA_CP_INITSET=0x0001
CONFIG_ESP32_UART=y
@ -203,6 +202,7 @@ CONFIG_PREALLOC_TIMERS=4
#
# Tasks and Scheduling
#
# CONFIG_SMP is not set
# CONFIG_INIT_NONE is not set
CONFIG_INIT_ENTRYPOINT=y
# CONFIG_INIT_FILEPATH is not set

View File

@ -75,7 +75,6 @@ CONFIG_ARCH_CHIP="esp32"
# CONFIG_SERIAL_TERMIOS is not set
CONFIG_ARCH_CHIP_ESP32=y
CONFIG_ARCH_FAMILY_LX6=y
CONFIG_XTENSA_CALL0_ABI=y
# CONFIG_XTENSA_USE_OVLY is not set
CONFIG_XTENSA_CP_INITSET=0x0001
CONFIG_ESP32_UART=y