Merge remote-tracking branch 'upstream/master'

This commit is contained in:
pnb 2015-12-22 13:29:31 +01:00
commit badc0c2215
29 changed files with 1677 additions and 124 deletions

View File

@ -238,6 +238,7 @@ config ARCH_CHIP_TMS570
select ARCH_HAVE_LOWVECTORS
select ARCH_HAVE_RAMFUNCS
select ARMV7R_MEMINIT
select ARMV7R_HAVE_DECODEFIQ
---help---
TI TMS570 family

View File

@ -885,7 +885,7 @@ arm_vectorfiq:
stmia r0, {r1-r4}
#endif
/* Then call the IRQ handler with interrupts disabled. */
/* Then call the FIQ handler with interrupts disabled. */
mov fp, #0 /* Init frame pointer */
mov r0, sp /* Get r0=xcp */

View File

@ -86,7 +86,7 @@
/* MPU Region Number Register Bit Definitions */
#ifdef CONFIG_ARM_MPU_NREGIONS <= 8
#if CONFIG_ARM_MPU_NREGIONS <= 8
# define MPU_RNR_MASK (0x00000007)
#elif CONFIG_ARM_MPU_NREGIONS <= 16
# define MPU_RNR_MASK (0x0000000f)

View File

@ -172,9 +172,14 @@ config ARMV7R_OABI_TOOLCHAIN
Most of the older buildroot toolchains are OABI and are named
arm-nuttx-elf- vs. arm-nuttx-eabi-
config ARMV7R_HAVE_DECODEFIQ
bool
default n
config ARMV7R_DECODEFIQ
bool "FIQ Handler"
default n
depends on ARMV7R_HAVE_DECODEFIQ
---help---
Select this option if your platform supports the function
arm_decodefiq().

View File

@ -112,8 +112,8 @@ up_fullcontextrestore:
vmsr fpscr, r2 /* Restore the FPCSR */
#endif
#ifdef CONFIG_BUILD_KERNEL
/* For the kernel build, we need to be able to transition gracefully
#ifdef CONFIG_BUILD_PROTECTED
/* For the protected build, we need to be able to transition gracefully
* between kernel- and user-mode tasks. Here we do that with a system
* call; the system call will execute in kernel mode and but can return
* to either user or kernel mode.

View File

@ -91,17 +91,25 @@
* - Clear .bss section (data should be fully initialized)
*/
/* Beginning (BOTTOM) and End+1 (TOP) of the IDLE stack.
/* Beginning (BOTTOM/BASE) and End+1 (TOP) of the IDLE stack.
*
* REVISIT: There are issues here. The stack point is initialized very
* early in the boot sequence, but in some architectures the memory supporting
* the may not be initialized (SDRAM, for example). In that case, ideally
* the IDLE stack should be in some other memory that does not require
* initialization (such as internal SRAM)
* The IDLE stack is the stack that is used during intialization and,
* eventually, becomes the stack of the IDLE task when initialization
* is complete.
*
* REVISIT: There are issues here in some configurations. The stack
* pointer is initialized very early in the boot sequence. But in some
* architectures the memory supporting the stack may not yet be
* initialized (SDRAM, for example, would not be ready yet). In that
* case, ideally the IDLE stack should be in some other memory that does
* not require initialization (such as internal SRAM)
*/
#define IDLE_STACK_BASE _ebss
#define IDLE_STACK_TOP _ebss+CONFIG_IDLETHREAD_STACKSIZE
#ifndef IDLE_STACK_BASE
# define IDLE_STACK_BASE _ebss
#endif
#define IDLE_STACK_TOP IDLE_STACK_BASE+CONFIG_IDLETHREAD_STACKSIZE
/****************************************************************************
* Global Symbols

View File

@ -45,7 +45,7 @@
#include "up_internal.h"
#if ((defined(CONFIG_BUILD_PROTECTED) && defined(__KERNEL__)) || \
defined(CONFIG_BUILD_KERNEL)) && !defined(CONFIG_DISABLE_SIGNALS)
defined(CONFIG_BUILD_PROTECTED)) && !defined(CONFIG_DISABLE_SIGNALS)
/****************************************************************************
* Pre-processor Definitions
@ -67,7 +67,7 @@
* Name: up_signal_dispatch
*
* Description:
* In this kernel mode build, this function will be called to execute a
* In the protected mode build, this function will be called to execute a
* a signal handler in user-space. When the signal is delivered, a
* kernel-mode stub will first run to perform some housekeeping functions.
* This kernel-mode stub will then be called transfer control to the user
@ -116,4 +116,4 @@ void up_signal_dispatch(_sa_sigaction_t sighand, int signo,
}
}
#endif /* (CONFIG_BUILD_PROTECTED || CONFIG_BUILD_KERNEL) && !CONFIG_DISABLE_SIGNALS */
#endif /* (CONFIG_BUILD_PROTECTED || CONFIG_BUILD_PROTECTED) && !CONFIG_DISABLE_SIGNALS */

View File

@ -160,7 +160,7 @@ static void dispatch_syscall(void)
uint32_t *arm_syscall(uint32_t *regs)
{
uint32_t cmd;
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
uint32_t cpsr;
#endif
@ -217,7 +217,7 @@ uint32_t *arm_syscall(uint32_t *regs)
*/
regs[REG_PC] = rtcb->xcp.syscall[index].sysreturn;
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
regs[REG_CPSR] = rtcb->xcp.syscall[index].cpsr;
#endif
/* The return value must be in R0-R1. dispatch_syscall() temporarily
@ -254,7 +254,7 @@ uint32_t *arm_syscall(uint32_t *regs)
* R1 = restoreregs
*/
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
case SYS_context_restore:
{
/* Replace 'regs' with the pointer to the register set in
@ -280,7 +280,7 @@ uint32_t *arm_syscall(uint32_t *regs)
* R3 = argv
*/
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
case SYS_task_start:
{
/* Set up to return to the user-space _start function in
@ -313,7 +313,7 @@ uint32_t *arm_syscall(uint32_t *regs)
* R2 = arg
*/
#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_PTHREAD)
#if defined(CONFIG_BUILD_PROTECTED) && !defined(CONFIG_DISABLE_PTHREAD)
case SYS_pthread_start:
{
/* Set up to return to the user-space pthread start-up function in
@ -334,7 +334,7 @@ uint32_t *arm_syscall(uint32_t *regs)
break;
#endif
#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
#if defined(CONFIG_BUILD_PROTECTED) && !defined(CONFIG_DISABLE_SIGNALS)
/* R0=SYS_signal_handler: This a user signal handler callback
*
* void signal_handler(_sa_sigaction_t sighand, int signo,
@ -399,7 +399,7 @@ uint32_t *arm_syscall(uint32_t *regs)
break;
#endif
#if defined(CONFIG_BUILD_KERNEL) && !defined(CONFIG_DISABLE_SIGNALS)
#if defined(CONFIG_BUILD_PROTECTED) && !defined(CONFIG_DISABLE_SIGNALS)
/* R0=SYS_signal_handler_return: This a user signal handler callback
*
* void signal_handler_return(void);
@ -465,12 +465,12 @@ uint32_t *arm_syscall(uint32_t *regs)
/* Setup to return to dispatch_syscall in privileged mode. */
rtcb->xcp.syscall[index].sysreturn = regs[REG_PC];
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
rtcb->xcp.syscall[index].cpsr = regs[REG_CPSR];
#endif
regs[REG_PC] = (uint32_t)dispatch_syscall;
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
cpsr = regs[REG_CPSR] & ~PSR_MODE_MASK;
regs[REG_CPSR] = cpsr | PSR_MODE_SVC;
#endif

View File

@ -128,7 +128,7 @@ arm_vectorirq:
ldr r0, .Lirqtmp /* Points to temp storage */
ldmia r0, {r3, r4} /* Recover r3=lr_IRQ, r4=spsr_IRQ */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode r13(sp) and r14(lr).
*/
@ -204,7 +204,7 @@ arm_vectorirq:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/
@ -265,7 +265,7 @@ arm_vectorsvc:
mov r3, r14 /* Save r14 as the PC as well */
mrs r4, spsr /* Get the saved CPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode r13(sp) and r14(lr).
*/
@ -333,7 +333,7 @@ arm_vectorsvc:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/
@ -407,7 +407,7 @@ arm_vectordata:
ldr r0, .Ldaborttmp /* Points to temp storage */
ldmia r0, {r3, r4} /* Recover r3=lr_ABT, r4=spsr_ABT */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode r13(sp) and r14(lr).
*/
@ -477,7 +477,7 @@ arm_vectordata:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr_cxsf, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/
@ -553,7 +553,7 @@ arm_vectorprefetch:
ldr r0, .Lpaborttmp /* Points to temp storage */
ldmia r0, {r3, r4} /* Recover r3=lr_ABT, r4=spsr_ABT */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode r13(sp) and r14(lr).
*/
@ -623,7 +623,7 @@ arm_vectorprefetch:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr_cxsf, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/
@ -696,7 +696,7 @@ arm_vectorundefinsn:
ldr r0, .Lundeftmp /* Points to temp storage */
ldmia r0, {r3, r4} /* Recover r3=lr_UND, r4=spsr_UND */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode r13(sp) and r14(lr).
*/
@ -764,7 +764,7 @@ arm_vectorundefinsn:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr_cxsf, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/
@ -839,7 +839,7 @@ arm_vectorfiq:
ldr r0, .Lfiqtmp /* Points to temp storage */
ldmia r0, {r3, r4} /* Recover r3=lr_SVC, r4=spsr_SVC */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Did we enter from user mode? If so then we need get the values of
* USER mode rr13(sp) and r14(lr).
*/
@ -885,7 +885,7 @@ arm_vectorfiq:
stmia r0, {r1-r4}
#endif
/* Then call the IRQ handler with interrupts disabled. */
/* Then call the FIQ handler with interrupts disabled. */
mov fp, #0 /* Init frame pointer */
mov r0, sp /* Get r0=xcp */
@ -915,7 +915,7 @@ arm_vectorfiq:
ldr r1, [r0, #(4*REG_CPSR)] /* Fetch the return SPSR */
msr spsr, r1 /* Set the return mode SPSR */
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* Are we leaving in user mode? If so then we need to restore the
* values of USER mode r13(sp) and r14(lr).
*/

View File

@ -106,7 +106,7 @@
/* MPU Region Number Register */
#ifdef CONFIG_ARM_MPU_NREGIONS <= 8
#if CONFIG_ARM_MPU_NREGIONS <= 8
# define MPU_RGNR_MASK (0x00000007)
#elif CONFIG_ARM_MPU_NREGIONS <= 16
# define MPU_RGNR_MASK (0x0000000f)

View File

@ -54,11 +54,11 @@
/* Configuration ********************************************************************/
/* This logic uses one system call for the syscall return. So a minimum of one
* syscall values must be reserved. If CONFIG_BUILD_KERNEL is defined, then four
* syscall values must be reserved. If CONFIG_BUILD_PROTECTED is defined, then four
* more syscall values must be reserved.
*/
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
# ifndef CONFIG_SYS_RESERVED
# error "CONFIG_SYS_RESERVED must be defined to have the value 6"
# elif CONFIG_SYS_RESERVED != 6
@ -81,7 +81,7 @@
#define SYS_syscall_return (0)
#ifdef CONFIG_BUILD_KERNEL
#ifdef CONFIG_BUILD_PROTECTED
/* SYS call 1:
*
* void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
@ -120,7 +120,7 @@
#define SYS_signal_handler_return (5)
#endif /* CONFIG_BUILD_KERNEL */
#endif /* CONFIG_BUILD_PROTECTED */
/************************************************************************************
* Inline Functions

View File

@ -135,11 +135,14 @@
# endif
# define up_restorestate(regs) (current_regs = regs)
/* The Cortex-A5 supports the same mechanism, but only lazy floating point
* register save/restore.
/* The Cortex-A and Cortex-R supports the same mechanism, but only lazy
* floating point register save/restore.
*/
#elif defined(CONFIG_ARCH_CORTEXA5) || defined(CONFIG_ARCH_CORTEXA8)
#elif defined(CONFIG_ARCH_CORTEXA5) || defined(CONFIG_ARCH_CORTEXA8) || \
defined(CONFIG_ARCH_CORTEXR4) || defined(CONFIG_ARCH_CORTEXR4F) || \
defined(CONFIG_ARCH_CORTEXR5) || defined(CONFIG_ARCH_CORTEXR5F) || \
defined(CONFIG_ARCH_CORTEXR7) || defined(CONFIG_ARCH_CORTEXR7F)
/* If the floating point unit is present and enabled, then save the
* floating point registers as well as normal ARM registers.
@ -348,11 +351,14 @@ int up_memfault(int irq, FAR void *context);
# endif /* CONFIG_ARCH_CORTEXM3,4,7 */
/* Exception handling logic unique to the Cortex-A family (but should be
* back-ported to the ARM7 and ARM9 families).
/* Exception handling logic unique to the Cortex-A and Cortex-R families
* (but should be back-ported to the ARM7 and ARM9 families).
*/
#elif defined(CONFIG_ARCH_CORTEXA5) || defined(CONFIG_ARCH_CORTEXA8)
#elif defined(CONFIG_ARCH_CORTEXA5) || defined(CONFIG_ARCH_CORTEXA8) || \
defined(CONFIG_ARCH_CORTEXR4) || defined(CONFIG_ARCH_CORTEXR4F) || \
defined(CONFIG_ARCH_CORTEXR5) || defined(CONFIG_ARCH_CORTEXR5F) || \
defined(CONFIG_ARCH_CORTEXR7) || defined(CONFIG_ARCH_CORTEXR7F)
/* Interrupt acknowledge and dispatch */

View File

@ -248,6 +248,16 @@ pid_t up_vfork(const struct vfork_s *context)
child->cmn.xcp.syscall[index].cpsr =
parent->xcp.syscall[index].cpsr;
# endif
#elif defined(CONFIG_ARCH_CORTEXR4) || defined(CONFIG_ARCH_CORTEXR4F) || \
defined(CONFIG_ARCH_CORTEXR5) || defined(CONFIG_ARCH_CORTEXR5F) || \
defined(CONFIG_ARCH_CORTEXR7) || defined(CONFIG_ARCH_CORTEXR7F)
# ifdef CONFIG_BUILD_PROTECTED
child->cmn.xcp.syscall[index].cpsr =
parent->xcp.syscall[index].cpsr;
# endif
#elif defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4) || \
defined(CONFIG_ARCH_CORTEXM0) || defined(CONFIG_ARCH_CORTEXM7)

View File

@ -182,6 +182,19 @@
# define ADC_MAX_SAMPLES ADC_MAX_CHANNELS_NODMA
#endif
#if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define ADC_DMA_CONTROL_WORD (DMA_SCR_MSIZE_16BITS | \
DMA_SCR_PSIZE_16BITS | \
DMA_SCR_MINC | \
DMA_SCR_CIRC | \
DMA_SCR_DIR_P2M)
#else
# define ADC_DMA_CONTROL_WORD (DMA_CCR_MSIZE_16BITS | \
DMA_CCR_PSIZE_16BITS | \
DMA_CCR_MINC | \
DMA_CCR_CIRC)
#endif
/* DMA channels and interface values differ for the F1 and F4 families */
#if defined(CONFIG_STM32_STM32F10XX)
@ -1923,8 +1936,6 @@ static void adc_reset(FAR struct adc_dev_s *dev)
if (priv->hasdma)
{
uint32_t ccr;
/* Stop and free DMA if it was started before */
if (priv->dma != NULL)
@ -1934,17 +1945,12 @@ static void adc_reset(FAR struct adc_dev_s *dev)
}
priv->dma = stm32_dmachannel(priv->dmachan);
ccr = DMA_SCR_MSIZE_16BITS | /* Memory size */
DMA_SCR_PSIZE_16BITS | /* Peripheral size */
DMA_SCR_MINC | /* Memory increment mode */
DMA_SCR_CIRC | /* Circular buffer */
DMA_SCR_DIR_P2M; /* Read from peripheral */
stm32_dmasetup(priv->dma,
priv->base + STM32_ADC_DR_OFFSET,
(uint32_t)priv->dmabuffer,
priv->nchannels,
ccr);
ADC_DMA_CONTROL_WORD);
stm32_dmastart(priv->dma, adc_dmaconvcallback, dev, false);
}

View File

@ -280,15 +280,7 @@
#undef ADC_HAVE_DMA
#if defined(CONFIG_STM32_ADC1_DMA) || defined(CONFIG_STM32_ADC2_DMA) || \
defined(CONFIG_STM32_ADC3_DMA) || defined(CONFIG_STM32_ADC4_DMA)
# if defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
# define ADC_HAVE_DMA 1
# else
# warning "DMA is only supported for the STM32 F2/F3/F4 families"
# undef CONFIG_STM32_ADC1_DMA
# undef CONFIG_STM32_ADC2_DMA
# undef CONFIG_STM32_ADC3_DMA
# undef CONFIG_STM32_ADC4_DMA
# endif
# define ADC_HAVE_DMA 1
#endif
#ifdef CONFIG_STM32_ADC1_DMA

View File

@ -106,3 +106,7 @@ CHIP_CSRCS = tms570_boot.c tms570_clockconfig.c tms570_irq.c
ifneq ($(CONFIG_SCHED_TICKLESS),y)
CHIP_CSRCS += tms570_timerisr.c
endif
ifneq ($(CONFIG_TMS570_SELFTEST),y)
CHIP_CSRCS += tms570_selftest.c
endif

View File

@ -0,0 +1,191 @@
/****************************************************************************************************
* arch/arm/src/tms570/chip/tms570_iomm.h
* I/O Muliplexing and Control Module (IOMM) Definitions
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
*
* TMS570LS04x/03x 16/32-Bit RISC Flash Microcontroller, Technical Reference Manual, Texas
* Instruments, Literature Number: SPNU517A, September 2013
*
* 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_ARM_SRC_TMS570_CHIP_TMS570_IOMM_H
#define __ARCH_ARM_SRC_TMS570_CHIP_TMS570_IOMM_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include "chip/tms570_memorymap.h"
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* Register Offsets *********************************************************************************/
#define TMS570_IOMM_REVISION_OFFSET 0x0000 /* Revision Register */
#define TMS570_IOMM_BOOT_OFFSET 0x0020 /* Boot Mode Register */
#define TMS570_IOMM_KICK0_OFFSET 0x0038 /* Kicker Register 0 */
#define TMS570_IOMM_KICK1_OFFSET 0x003c /* Kicker Register 1 */
#define TMS570_IOMM_ERRRAWSTATUS_OFFSET 0x00e0 /* Error Raw Status / Set Register */
#define TMS570_IOMM_ERRSTATUS_OFFSET 0x00e4 /* Error Enabled Status / Clear Register */
#define TMS570_IOMM_ERRENABLE_OFFSET 0x00e8 /* Error Signaling Enable Register */
#define TMS570_IOMM_ERRENABLECLR_OFFSET 0x00ec /* Error Signaling Enable Clear Register */
#define TMS570_IOMM_FAULTADDRESS_OFFSET 0x00f4 /* Fault Address Register */
#define TMS570_IOMM_FAULTSTATUS_OFFSET 0x00f8 /* Fault Status Register */
#define TMS570_IOMM_FAULTCLR_OFFSET 0x00fc /* Fault Clear Register */
#define TMS570_IOMM_PINMMR_OFFSET(n) (0x0110 + ((unsigned int)(n) << 2))
# define TMS570_IOMM_PINMMR0_OFFSET 0x0110 /* Pin Multiplexing Control Register 0 */
# define TMS570_IOMM_PINMMR1_OFFSET 0x0114 /* Pin Multiplexing Control Register 1 */
# define TMS570_IOMM_PINMMR2_OFFSET 0x0118 /* Pin Multiplexing Control Register 2 */
# define TMS570_IOMM_PINMMR3_OFFSET 0x011c /* Pin Multiplexing Control Register 3 */
# define TMS570_IOMM_PINMMR4_OFFSET 0x0120 /* Pin Multiplexing Control Register 4 */
# define TMS570_IOMM_PINMMR5_OFFSET 0x0124 /* Pin Multiplexing Control Register 5 */
# define TMS570_IOMM_PINMMR6_OFFSET 0x0128 /* Pin Multiplexing Control Register 6 */
# define TMS570_IOMM_PINMMR7_OFFSET 0x012c /* Pin Multiplexing Control Register 7 */
# define TMS570_IOMM_PINMMR8_OFFSET 0x0130 /* Pin Multiplexing Control Register 8 */
# define TMS570_IOMM_PINMMR9_OFFSET 0x0134 /* Pin Multiplexing Control Register 9 */
# define TMS570_IOMM_PINMMR10_OFFSET 0x0138 /* Pin Multiplexing Control Register 10 */
# define TMS570_IOMM_PINMMR11_OFFSET 0x013c /* Pin Multiplexing Control Register 11 */
# define TMS570_IOMM_PINMMR12_OFFSET 0x0140 /* Pin Multiplexing Control Register 12 */
# define TMS570_IOMM_PINMMR13_OFFSET 0x0144 /* Pin Multiplexing Control Register 13 */
# define TMS570_IOMM_PINMMR14_OFFSET 0x0148 /* Pin Multiplexing Control Register 14 */
# define TMS570_IOMM_PINMMR15_OFFSET 0x014c /* Pin Multiplexing Control Register 15 */
# define TMS570_IOMM_PINMMR16_OFFSET 0x0150 /* Pin Multiplexing Control Register 16 */
# define TMS570_IOMM_PINMMR17_OFFSET 0x0154 /* Pin Multiplexing Control Register 17 */
# define TMS570_IOMM_PINMMR18_OFFSET 0x0158 /* Pin Multiplexing Control Register 18 */
# define TMS570_IOMM_PINMMR19_OFFSET 0x015c /* Pin Multiplexing Control Register 19 */
# define TMS570_IOMM_PINMMR20_OFFSET 0x0160 /* Pin Multiplexing Control Register 20 */
# define TMS570_IOMM_PINMMR21_OFFSET 0x0164 /* Pin Multiplexing Control Register 21 */
# define TMS570_IOMM_PINMMR22_OFFSET 0x0168 /* Pin Multiplexing Control Register 22 */
# define TMS570_IOMM_PINMMR23_OFFSET 0x016c /* Pin Multiplexing Control Register 23 */
# define TMS570_IOMM_PINMMR24_OFFSET 0x0170 /* Pin Multiplexing Control Register 24 */
# define TMS570_IOMM_PINMMR25_OFFSET 0x0174 /* Pin Multiplexing Control Register 25 */
# define TMS570_IOMM_PINMMR26_OFFSET 0x0178 /* Pin Multiplexing Control Register 26 */
# define TMS570_IOMM_PINMMR27_OFFSET 0x017c /* Pin Multiplexing Control Register 27 */
# define TMS570_IOMM_PINMMR28_OFFSET 0x0180 /* Pin Multiplexing Control Register 28 */
# define TMS570_IOMM_PINMMR29_OFFSET 0x0184 /* Pin Multiplexing Control Register 29 */
# define TMS570_IOMM_PINMMR30_OFFSET 0x0188 /* Pin Multiplexing Control Register 30 */
/* Register Addresses *******************************************************************************/
#define TMS570_IOMM_REVISION (TMS570_IOMM_BASE+TMS570_IOMM_REVISION_OFFSET)
#define TMS570_IOMM_BOOT (TMS570_IOMM_BASE+TMS570_IOMM_BOOT_OFFSET)
#define TMS570_IOMM_KICK0 (TMS570_IOMM_BASE+TMS570_IOMM_KICK0_OFFSET)
#define TMS570_IOMM_KICK1 (TMS570_IOMM_BASE+TMS570_IOMM_KICK1_OFFSET)
#define TMS570_IOMM_ERRRAWSTATUS (TMS570_IOMM_BASE+TMS570_IOMM_ERRRAWSTATUS_OFFSET)
#define TMS570_IOMM_ERRSTATUS (TMS570_IOMM_BASE+TMS570_IOMM_ERRSTATUS_OFFSET)
#define TMS570_IOMM_ERRENABLE (TMS570_IOMM_BASE+TMS570_IOMM_ERRENABLE_OFFSET)
#define TMS570_IOMM_ERRENABLECLR (TMS570_IOMM_BASE+TMS570_IOMM_ERRENABLECLR_OFFSET)
#define TMS570_IOMM_FAULTADDRESS (TMS570_IOMM_BASE+TMS570_IOMM_FAULTADDRESS_OFFSET)
#define TMS570_IOMM_FAULTSTATUS (TMS570_IOMM_BASE+TMS570_IOMM_FAULTSTATUS_OFFSET)
#define TMS570_IOMM_FAULTCLR (TMS570_IOMM_BASE+TMS570_IOMM_FAULTCLR_OFFSET)
#define TMS570_IOMM_PINMMR(n) (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR_OFFSET(n))
# define TMS570_IOMM_PINMMR0 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR0_OFFSET)
# define TMS570_IOMM_PINMMR1 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR1_OFFSET)
# define TMS570_IOMM_PINMMR2 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR2_OFFSET)
# define TMS570_IOMM_PINMMR3 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR3_OFFSET)
# define TMS570_IOMM_PINMMR4 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR4_OFFSET)
# define TMS570_IOMM_PINMMR5 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR5_OFFSET)
# define TMS570_IOMM_PINMMR6 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR6_OFFSET)
# define TMS570_IOMM_PINMMR7 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR7_OFFSET)
# define TMS570_IOMM_PINMMR8 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR8_OFFSET)
# define TMS570_IOMM_PINMMR9 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR9_OFFSET)
# define TMS570_IOMM_PINMMR10 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR10_OFFSET)
# define TMS570_IOMM_PINMMR11 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR11_OFFSET)
# define TMS570_IOMM_PINMMR12 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR12_OFFSET)
# define TMS570_IOMM_PINMMR13 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR13_OFFSET)
# define TMS570_IOMM_PINMMR14 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR14_OFFSET)
# define TMS570_IOMM_PINMMR15 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR15_OFFSET)
# define TMS570_IOMM_PINMMR16 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR16_OFFSET)
# define TMS570_IOMM_PINMMR17 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR17_OFFSET)
# define TMS570_IOMM_PINMMR18 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR18_OFFSET)
# define TMS570_IOMM_PINMMR19 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR19_OFFSET)
# define TMS570_IOMM_PINMMR20 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR20_OFFSET)
# define TMS570_IOMM_PINMMR21 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR21_OFFSET)
# define TMS570_IOMM_PINMMR22 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR22_OFFSET)
# define TMS570_IOMM_PINMMR23 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR23_OFFSET)
# define TMS570_IOMM_PINMMR24 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR24_OFFSET)
# define TMS570_IOMM_PINMMR25 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR25_OFFSET)
# define TMS570_IOMM_PINMMR26 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR26_OFFSET)
# define TMS570_IOMM_PINMMR27 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR27_OFFSET)
# define TMS570_IOMM_PINMMR28 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR28_OFFSET)
# define TMS570_IOMM_PINMMR29 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR29_OFFSET)
# define TMS570_IOMM_PINMMR30 (TMS570_IOMM_BASE+TMS570_IOMM_PINMMR30_OFFSET)
/* Register Bit-Field Definitions *******************************************************************/
/* Revision Register */
#define IOMM_REVISION_
/* Boot Mode Register */
#define IOMM_BOOT_
/* Kicker Register 0 */
#define IOMM_KICK0_UNLOCK 0x83e70b13 /* Unlock value */
#define IOMM_KICK0_LOCK 0x00000000 /* Any other value locks */
/* Kicker Register 1 */
#define IOMM_KICK1_UNLOCK 0x95a4f1e0 /* Unlock value */
#define IOMM_KICK1_LOCK 0x00000000 /* Any other value locks */
/* Error Raw Status / Set Register */
#define IOMM_ERRRAWSTATUS_
/* Error Enabled Status / Clear Register */
#define IOMM_ERRSTATUS_
/* Error Signaling Enable Register */
#define IOMM_ERRENABLE_
/* Error Signaling Enable Clear Register */
#define IOMM_ERRENABLECLR_
/* Fault Address Register */
#define IOMM_FAULTADDRESS_
/* Fault Status Register */
#define IOMM_FAULTSTATUS_
/* Fault Clear Register */
#define IOMM_FAULTCLR_
/* Pin Multiplexing Control Register n, n=0..30. Each 8-bit field controls the functionality of
* one pin/ball. There are then a maximum of 31*4 = 124 pin/ball configurations supported.
*/
#define IOMM_PINMMR_REGNDX(n) ((n) >> 2)
#define IOMM_PINMMR_PINSHIFT(n) (((n) & 3) << 3)
#define IOMM_PINMMR_PINMASK(n) (0xff << IOMM_PINMMR_PINSHIFT(n))
# define IOMM_PINMMR_PINVALUE(n,v) ((uint32_t)(v) << IOMM_PINMMR_PINSHIFT(n))
#endif /* __ARCH_ARM_SRC_TMS570_CHIP_TMS570_IOMM_H */

View File

@ -52,6 +52,31 @@
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* PBIST RAM Groups */
#define PBIST_PBIST_ROM_GROUP 1 /* ROM */
#define PBIST_STC_ROM_GROUP 2 /* ROM */
#define PBIST_DCAN1_RAM_GROUP 3 /* Dual-port */
#define PBIST_DCAN2_RAM_GROUP 4 /* Dual-port */
#define PBIST_ESRAM1_RAM_GROUP 6 /* Single-port */
#define PBIST_MIBSPI1_RAM_GROUP 7 /* Dual-port */
#define PBIST_VIM_RAM_GROUP 10 /* Dual-port */
#define PBIST_MIBADC_RAM_GROUP 11 /* Dual-port */
#define PBIST_N2HET_RAM_GROUP 13 /* Dual-port */
#define PBIST_HET_TU_RAM_GROUP 14 /* Dual-port */
/* RAM Group Select */
#define PBIST_PBIST_ROM_RGS 1 /* ROM */
#define PBIST_STC_ROM_RGS 2 /* ROM */
#define PBIST_DCAN1_RAM_RGS 3 /* Dual-port */
#define PBIST_DCAN2_RAM_RGS 4 /* Dual-port */
#define PBIST_ESRAM1_RAM_RGS 6 /* Single-port */
#define PBIST_MIBSPI1_RAM_RGS 7 /* Dual-port */
#define PBIST_VIM_RAM_RGS 8 /* Dual-port */
#define PBIST_MIBADC_RAM_RGS 9 /* Dual-port */
#define PBIST_N2HET_RAM_RGS 11 /* Dual-port */
#define PBIST_HET_TU_RAM_RGS 12 /* Dual-port */
/* Register Offsets *********************************************************************************/
@ -125,8 +150,21 @@
#define PBIST_ROM_
/* ROM Algorithm Mask Register */
#define PBIST_ALGO_
/* RAM Info Mask Lower Register */
#define PBIST_RINFOL_
#define PBIST_RINFOL(n) (1 << ((n)-1)) /* Bit n: Select RAM group n+1 */
# define PBIST_RINFOL_PBIST_ROM PBIST_RINFOL(PBIST_PBIST_ROM_GROUP)
# define PBIST_RINFOL_STC_ROM PBIST_RINFOL(PBIST_STC_ROM_GROUP)
# define PBIST_RINFOL_DCAN1_RAM PBIST_RINFOL(PBIST_DCAN1_RAM_GROUP)
# define PBIST_RINFOL_DCAN2_RAM PBIST_RINFOL(PBIST_DCAN2_RAM_GROUP)
# define PBIST_RINFOL_ESRAM1_RAM PBIST_RINFOL(PBIST_ESRAM1_RAM_GROUP)
# define PBIST_RINFOL_MIBSPI1_RAM PBIST_RINFOL(PBIST_MIBSPI1_RAM_GROUP)
# define PBIST_RINFOL_VIM_RAM PBIST_RINFOL(PBIST_VIM_RAM_GROUP)
# define PBIST_RINFOL_MIBADC_RAM PBIST_RINFOL(PBIST_MIBADC_RAM_GROUP)
# define PBIST_RINFOL_N2HET_RAM PBIST_RINFOL(PBIST_N2HET_RAM_GROUP)
# define PBIST_RINFOL_HET_TU_RAM PBIST_RINFOL(PBIST_HET_TU_RAM_GROUP)
/* RAM Info Mask Upper Register */
#define PBIST_RINFOU_

View File

@ -0,0 +1,76 @@
/****************************************************************************************************
* arch/arm/src/tms570/chip/tms570_pinmux.h
*
* Copyright (C) 2015 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_ARM_SRC_TMS570_CHIP_TMS570_PINMUX_H
#define __ARCH_ARM_SRC_TMS570_CHIP_TMS570_PINMUX_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#if defined(CONFIG_ARCH_CHIP_TMS570LS0232PZ)
# error No pin multiplexing for the TMS570LS0232PZ
#elif defined(CONFIG_ARCH_CHIP_TMS570LS0332PZ)
# include "chip/tms570ls04x03x_pinmux.h"
#elif defined(CONFIG_ARCH_CHIP_TMS570LS0432PZ)
# include "chip/tms570ls04x03x_pinmux.h"
#elif defined(CONFIG_ARCH_CHIP_TMS570LS0714PZ)
# error No pin multiplexing for the TMS570LS0714PZ
#elif defined(CONFIG_ARCH_CHIP_TMS570LS0714PGE)
# error No pin multiplexing for the TMS570LS0714PGE
#elif defined(CONFIG_ARCH_CHIP_TMS570LS0714ZWT)
# error No pin multiplexing for the TMS570LS0714ZWT
#elif defined(CONFIG_ARCH_CHIP_TMS570LS1227ZWT)
# error No pin multiplexing for the TMS570LS1227ZWT
#else
# error "Unrecognized Hercules chip"
#endif
/****************************************************************************************************
* Pulbic Type Definitions
****************************************************************************************************/
/* Each chip-specific pinmux header file defines initializers for a type like: */
struct tms570_pinmux_s
{
uint8_t mmrndx; /* Index to the PINMMR register, 0-30 */
uint8_t shift; /* Shift value to isolate the pin field in the PINMMR register */
uint8_t value; /* The new value for the pin field in the PINMMR register */
};
#endif /* __ARCH_ARM_SRC_TMS570_CHIP_TMS570_PINMUX_H */

View File

@ -0,0 +1,218 @@
/****************************************************************************************************
* arch/arm/src/tms570/chip/tms570_vim.h
* Vector Intererrupt Manager (VIM) Register Definitions
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
*
* TMS570LS04x/03x 16/32-Bit RISC Flash Microcontroller, Technical Reference Manual, Texas
* Instruments, Literature Number: SPNU517A, September 2013
*
* 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_ARM_SRC_TMS570_CHIP_TMS570_VIM_H
#define __ARCH_ARM_SRC_TMS570_CHIP_TMS570_VIM_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include "chip/tms570_memorymap.h"
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
#define VIM_REGNDX(ch) ((ch) >> 5)
#define VIM_REGBIT(ch) ((ch) & 31)
/* Register Offsets *********************************************************************************/
/* Register Offsets relative to the VIM Parity Frame */
#define TMS570_VIM_PARFLG_OFFSET 0x00ec /* Interrupt Vector Table Parity Flag Register */
#define TMS570_VIM_PARCTL_OFFSET 0x00f0 /* Interrupt Vector Table Parity Control Register */
#define TMS570_VIM_ADDERR_OFFSET 0x00f4 /* Address Parity Error Register */
#define TMS570_VIM_FBPARERR_OFFSET 0x00f8 /* Fall-Back Address Parity Error Register */
/* Register Offsets relative to the VIM Frame */
#define TMS570_VIM_IRQINDEX_OFFSET 0x0000 /* IRQ Index Offset Vector Register */
#define TMS570_VIM_FIQINDEX_OFFSET 0x0004 /* FIQ Index Offset Vector Register */
#define TMS570_VIM_FIRQPR_OFFSET(n) (0x0010 + ((n) << 2))
# define TMS570_VIM_FIRQPR0_OFFSET 0x0010 /* FIQ/IRQ Program Control Register 0 */
# define TMS570_VIM_FIRQPR1_OFFSET 0x0014 /* FIQ/IRQ Program Control Register 1 */
# define TMS570_VIM_FIRQPR2_OFFSET 0x0018 /* FIQ/IRQ Program Control Register 2 */
#define TMS570_VIM_INTREQ_OFFSET(n) (0x0020 + ((n) << 2))
# define TMS570_VIM_INTREQ0_OFFSET 0x0020 /* Pending Interrupt Read Location Register 0 */
# define TMS570_VIM_INTREQ1_OFFSET 0x0024 /* Pending Interrupt Read Location Register 1 */
# define TMS570_VIM_INTREQ2_OFFSET 0x0028 /* Pending Interrupt Read Location Register 2 */
#define TMS570_VIM_REQENASET_OFFSET(n) (0x0030 + ((n) << 2))
# define TMS570_VIM_REQENASET0_OFFSET 0x0030 /* Interrupt Enable Set Register 0 */
# define TMS570_VIM_REQENASET1_OFFSET 0x0034 /* Interrupt Enable Set Register 1 */
# define TMS570_VIM_REQENASET2_OFFSET 0x0038 /* Interrupt Enable Set Register 2 */
#define TMS570_VIM_REQENACLR_OFFSET(n) (0x0040 + ((n) << 2))
# define TMS570_VIM_REQENACLR0_OFFSET 0x0040 /* Interrupt Enable Clear Register 0 */
# define TMS570_VIM_REQENACLR1_OFFSET 0x0044 /* Interrupt Enable Clear Register 1 */
# define TMS570_VIM_REQENACLR2_OFFSET 0x0048 /* Interrupt Enable Clear Register 2 */
#define TMS570_VIM_WAKEENASET_OFFSET(n) (0x0050 + ((n) << 2))
# define TMS570_VIM_WAKEENASET0_OFFSET 0x0050 /* Wake-up Enable Set Register 0 */
# define TMS570_VIM_WAKEENASET1_OFFSET 0x0054 /* Wake-up Enable Set Register 1 */
# define TMS570_VIM_WAKEENASET2_OFFSET 0x0058 /* Wake-up Enable Set Register 2 */
#define TMS570_VIM_WAKEENACLR_OFFSET(n) (0x0060 + ((n) << 2))
# define TMS570_VIM_WAKEENACLR0_OFFSET 0x0060 /* Wake-up Enable Clear Register 0 */
# define TMS570_VIM_WAKEENACLR1_OFFSET 0x0064 /* Wake-up Enable Clear Register 1 */
# define TMS570_VIM_WAKEENACLR2_OFFSET 0x0068 /* Wake-up Enable Clear Register 2 */
#define TMS570_VIM_IRQVECREG_OFFSET 0x0070 /* IRQ Interrupt Vector Register */
#define TMS570_VIM_FIQVECREG_OFFSET 0x0074 /* FIQ Interrupt Vector Register */
#define TMS570_VIM_CAPEVT_OFFSET 0x0078 /* Capture Event Register */
/* 0x0080-0x00dc VIM Interrupt Control Register */
#define TMS570_VIM_CHANCTRL_INDEX(n) ((n) >> 2)
#define TMS570_VIM_CHANCTRL_OFFSET(n) (0x0080 << (TMS570_VIM_CHANCTRL_INDEX(n) << 2))
/* Register Addresses *******************************************************************************/
/* VIM Parity Frame Registers */
#define TMS570_VIM_PARFLG (TMS570_VIMPAR_BASE+TMS570_VIM_PARFLG_OFFSET)
#define TMS570_VIM_PARCTL (TMS570_VIMPAR_BASE+TMS570_VIM_PARCTL_OFFSET)
#define TMS570_VIM_ADDERR (TMS570_VIMPAR_BASE+TMS570_VIM_ADDERR_OFFSET)
#define TMS570_VIM_FBPARERR (TMS570_VIMPAR_BASE+TMS570_VIM_FBPARERR_OFFSET)
/* VIM Frame Registers */
#define TMS570_VIM_IRQINDEX (TMS570_VIM_BASE+TMS570_VIM_IRQINDEX_OFFSET)
#define TMS570_VIM_FIQINDEX (TMS570_VIM_BASE+TMS570_VIM_FIQINDEX_OFFSET)
#define TMS570_VIM_FIRQPR(n) (TMS570_VIM_BASE+TMS570_VIM_FIRQPR_OFFSET(n))
# define TMS570_VIM_FIRQPR0 (TMS570_VIM_BASE+TMS570_VIM_FIRQPR0_OFFSET)
# define TMS570_VIM_FIRQPR1 (TMS570_VIM_BASE+TMS570_VIM_FIRQPR1_OFFSET)
# define TMS570_VIM_FIRQPR2 (TMS570_VIM_BASE+TMS570_VIM_FIRQPR2_OFFSET)
#define TMS570_VIM_INTREQ(n) (TMS570_VIM_BASE+TMS570_VIM_INTREQ_OFFSET(n))
# define TMS570_VIM_INTREQ0 (TMS570_VIM_BASE+TMS570_VIM_INTREQ0_OFFSET)
# define TMS570_VIM_INTREQ1 (TMS570_VIM_BASE+TMS570_VIM_INTREQ1_OFFSET)
# define TMS570_VIM_INTREQ2 (TMS570_VIM_BASE+TMS570_VIM_INTREQ2_OFFSET)
#define TMS570_VIM_REQENASET(n) (TMS570_VIM_BASE+TMS570_VIM_REQENASET_OFFSET(n))
# define TMS570_VIM_REQENASET0 (TMS570_VIM_BASE+TMS570_VIM_REQENASET0_OFFSET)
# define TMS570_VIM_REQENASET1 (TMS570_VIM_BASE+TMS570_VIM_REQENASET1_OFFSET)
# define TMS570_VIM_REQENASET2 (TMS570_VIM_BASE+TMS570_VIM_REQENASET2_OFFSET)
#define TMS570_VIM_REQENACLR(n) (TMS570_VIM_BASE+TMS570_VIM_REQENACLR_OFFSET(n))
# define TMS570_VIM_REQENACLR0 (TMS570_VIM_BASE+TMS570_VIM_REQENACLR0_OFFSET)
# define TMS570_VIM_REQENACLR1 (TMS570_VIM_BASE+TMS570_VIM_REQENACLR1_OFFSET)
# define TMS570_VIM_REQENACLR2 (TMS570_VIM_BASE+TMS570_VIM_REQENACLR2_OFFSET)
#define TMS570_VIM_WAKEENASET(n) (TMS570_VIM_BASE+TMS570_VIM_WAKEENASET_OFFSET(n))
# define TMS570_VIM_WAKEENASET0 (TMS570_VIM_BASE+TMS570_VIM_WAKEENASET0_OFFSET)
# define TMS570_VIM_WAKEENASET1 (TMS570_VIM_BASE+TMS570_VIM_WAKEENASET1_OFFSET)
# define TMS570_VIM_WAKEENASET2 (TMS570_VIM_BASE+TMS570_VIM_WAKEENASET2_OFFSET)
#define TMS570_VIM_WAKEENACLR(n) (TMS570_VIM_BASE+TMS570_VIM_WAKEENACLR_OFFSET(n))
# define TMS570_VIM_WAKEENACLR0 (TMS570_VIM_BASE+TMS570_VIM_WAKEENACLR0_OFFSET)
# define TMS570_VIM_WAKEENACLR1 (TMS570_VIM_BASE+TMS570_VIM_WAKEENACLR1_OFFSET)
# define TMS570_VIM_WAKEENACLR2 (TMS570_VIM_BASE+TMS570_VIM_WAKEENACLR2_OFFSET)
#define TMS570_VIM_IRQVECREG (TMS570_VIM_BASE+TMS570_VIM_IRQVECREG_OFFSET)
#define TMS570_VIM_FIQVECREG (TMS570_VIM_BASE+TMS570_VIM_FIQVECREG_OFFSET)
#define TMS570_VIM_CAPEVT (TMS570_VIM_BASE+TMS570_VIM_CAPEVT_OFFSET)
/* 0x0080-0x00dc VIM Interrupt Control Register */
#define TMS570_VIM_CHANCTRL(n) (TMS570_VIM_BASE+TMS570_VIM_CHANCTRL_OFFSET(n))
/* Register Bit-Field Definitions *******************************************************************/
/* Interrupt Vector Table Parity Flag Register */
#define VIM_PARFLG_
/* Interrupt Vector Table Parity Control Register */
#define VIM_PARCTL_
/* Address Parity Error Register */
#define VIM_ADDERR_
/* Fall-Back Address Parity Error Register */
#define VIM_FBPARERR_
/* IRQ Index Offset Vector Register */
#define VIM_IRQINDEX_MASK (0x000000ff) /* IRQ index vector */
/* FIQ Index Offset Vector Register */
#define VIM_FIQINDEX_MASK (0x000000ff) /* FIQ index vector */
/* FIQ/IRQ Program Control Register 0 */
#define VIM_FIRQPR0_
/* FIQ/IRQ Program Control Register 1 */
#define VIM_FIRQPR1_
/* FIQ/IRQ Program Control Register 2 */
#define VIM_FIRQPR2_
/* Pending Interrupt Read Location Register 0 */
#define VIM_INTREQ0_
/* Pending Interrupt Read Location Register 1 */
#define VIM_INTREQ1_
/* Pending Interrupt Read Location Register 2 */
#define VIM_INTREQ2_
/* Interrupt Enable Set Register 0 */
#define VIM_REQENASET0_
/* Interrupt Enable Set Register 1 */
#define VIM_REQENASET1_
/* Interrupt Enable Set Register 2 */
#define VIM_REQENASET2_
/* Interrupt Enable Clear Register 0 */
#define VIM_REQENACLR0_
/* Interrupt Enable Clear Register 1 */
#define VIM_REQENACLR1_
/* Interrupt Enable Clear Register 2 */
#define VIM_REQENACLR2_
/* Wake-up Enable Set Register 0 */
#define VIM_WAKEENASET0_
/* Wake-up Enable Set Register 1 */
#define VIM_WAKEENASET1_
/* Wake-up Enable Set Register 2 */
#define VIM_WAKEENASET2_
/* Wake-up Enable Clear Register 0 */
#define VIM_WAKEENACLR0_
/* Wake-up Enable Clear Register 1 */
#define VIM_WAKEENACLR1_
/* Wake-up Enable Clear Register 2 */
#define VIM_WAKEENACLR2_
/* IRQ Interrupt Vector Register */
#define VIM_IRQVECREG_
/* FIQ Interrupt Vector Register */
#define VIM_FIQVECREG_
/* Capture Event Register */
#define VIM_CAPEVT_
/* 0x0080-0x00dc VIM Interrupt Control Register */
#define VIM_CHANCTRL_SHIFT(n) (((n) & 3) << 3)
#define VIM_CHANCTRL_MASK(n) (0xff << VIM_CHANCTRL_SHIFT(n))
# define VIM_CHANCTRL(n,v) ((uint32_t)(v) << VIM_CHANCTRL_SHIFT(n))
#endif /* __ARCH_ARM_SRC_TMS570_CHIP_TMS570_VIM_H */

View File

@ -0,0 +1,257 @@
/****************************************************************************************************
* arch/arm/src/tms570/chip/tms570ls04x03x_pinmux.h
* Secondary System Control Register Definitions
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
*
* TMS570LS04x/03x 16/32-Bit RISC Flash Microcontroller, Technical Reference Manual, Texas
* Instruments, Literature Number: SPNU517A, September 2013
*
* 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_ARM_SRC_TMS570_CHIP_TMS570LS04X03X_PINMUX_H
#define __ARCH_ARM_SRC_TMS570_CHIP_TMS570LS04X03X_PINMUX_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include "chip/tms570_memorymap.h"
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* DEFAULT SELECTION ALTERNATE SELECTION ALTERNATE SELECTION BIT
* FUNCTION BIT FUNCTION 1 BIT FUNCTION 2 BIT
*
* GIOA[0] PINMMR0[8] SPI3nCS[3] PINMMR0[9] - -
* GIOA[1] PINMMR1[0] SPI3nCS[2] PINMMR1[1] - -
* GIOA[2] PINMMR1[8] SPI3nCS[1] PINMMR1[9] - -
* GIOA[3] PINMMR1[16] SPI2nCS[3] PINMMR1[17] - -
* GIOA[4] PINMMR1[24] SPI2nCS[2] PINMMR1[25] - -
* GIOA[5] PINMMR2[0] EXTCLKIN PINMMR2[1] - -
* GIOA[6] PINMMR2[8] SPI2nCS[1] PINMMR2[9] N2HET[31] PINMMR2[10]
* GIOA[7] PINMMR2[16] N2HET[29] PINMMR2[17] - -
* MIBSPI1nCS[2] PINMMR3[0] N2HET[20] PINMMR3[1] N2HET[19] PINMMR3[2]
* SPI3CLK PINMMR3[16] EQEPA PINMMR3[17] - -
* SPI3nENA PINMMR3[24] EQEPB PINMMR3[25] - -
* SPI3nCS[0] PINMMR4[0] EQEPI PINMMR4[1] - -
* MIBSPI1nCS[3] PINMMR4[8] N2HET[26] PINMMR4[9] - -
* ADEVT PINMMR4[16] N2HET[28] PINMMR4[17] - -
* MIBSPI1nENA PINMMR5[8] N2HET[23] PINMMR5[9] NHET[30] PINMMR5[10]
* MIBSPI1nCS[1] PINMMR6[8] EQEPS PINMMR6[9] N2HET[17] PINMMR6[10]
*/
#define PINMUX_GIOA0_PINMMR 0
#define PINMUX_GIOA0_SHIFT 8
#define PINMUX_GIOA0_VALUE 1
#define PINMUX_GIOA0_PIN {PINMUX_GIOA0_PINMMR, PINMUX_GIOA0_SHIFT, PINMUX_GIOA0_VALUE}
#define PINMUX_SPI3NCS3_PINMMR 0
#define PINMUX_SPI3NCS3_SHIFT 8
#define PINMUX_SPI3NCS3_VALUE 2
#define PINMUX_SPI3NCS3_PIN {PINMUX_SPI3NCS3_PINMMR, PINMUX_SPI3NCS3_SHIFT, PINMUX_SPI3NCS3_VALUE}
#define PINMUX_GIOA1_PINMMR 1
#define PINMUX_GIOA1_SHIFT 0
#define PINMUX_GIOA1_VALUE 1
#define PINMUX_GIOA1_PIN {PINMUX_GIOA1_PINMMR, PINMUX_GIOA1_SHIFT, PINMUX_GIOA1_VALUE}
#define PINMUX_SPI3NCS2_PINMMR 1
#define PINMUX_SPI3NCS2_SHIFT 0
#define PINMUX_SPI3NCS2_VALUE 2
#define PINMUX_SPI3NCS2_PIN {PINMUX_SPI3NCS2_PINMMR, PINMUX_SPI3NCS2_SHIFT, PINMUX_SPI3NCS2_VALUE}
#define PINMUX_GIOA2_PINMMR 1
#define PINMUX_GIOA2_SHIFT 8
#define PINMUX_GIOA2_VALUE 1
#define PINMUX_GIOA2_PIN {PINMUX_GIOA2_PINMMR, PINMUX_GIOA2_SHIFT, PINMUX_GIOA2_VALUE}
#define PINMUX_SPI3NCS1_PINMMR 1
#define PINMUX_SPI3NCS1_SHIFT 8
#define PINMUX_SPI3NCS1_VALUE 2
#define PINMUX_SPI3NCS1_PIN {PINMUX_SPI3NCS1_PINMMR, PINMUX_SPI3NCS1_SHIFT, PINMUX_SPI3NCS1_VALUE}
#define PINMUX_GIOA3_PINMMR 1
#define PINMUX_GIOA3_SHIFT 16
#define PINMUX_GIOA3_VALUE 1
#define PINMUX_GIOA3_PIN {PINMUX_GIOA3_PINMMR, PINMUX_GIOA3_SHIFT, PINMUX_GIOA3_VALUE}
#define PINMUX_SPI2NCS3_PINMMR 1
#define PINMUX_SPI2NCS3_SHIFT 16
#define PINMUX_SPI2NCS3_VALUE 2
#define PINMUX_SPI2NCS3_PIN {PINMUX_SPI2NCS3_PINMMR, PINMUX_SPI2NCS3_SHIFT, PINMUX_SPI2NCS3_VALUE}
#define PINMUX_GIOA4_PINMMR 1
#define PINMUX_GIOA4_SHIFT 24
#define PINMUX_GIOA4_VALUE 1
#define PINMUX_GIOA4_PIN {PINMUX_GIOA4_PINMMR, PINMUX_GIOA4_SHIFT, PINMUX_GIOA4_VALUE}
#define PINMUX_SPI2NCS2_PINMMR 1
#define PINMUX_SPI2NCS2_SHIFT 24
#define PINMUX_SPI2NCS2_VALUE 2
#define PINMUX_SPI2NCS2_PIN {PINMUX_SPI2NCS2_PINMMR, PINMUX_SPI2NCS2_SHIFT, PINMUX_SPI2NCS2_VALUE}
#define PINMUX_GIOA5_PINMMR 2
#define PINMUX_GIOA5_SHIFT 0
#define PINMUX_GIOA5_VALUE 1
#define PINMUX_GIOA5_PIN {PINMUX_GIOA5_PINMMR, PINMUX_GIOA5_SHIFT, PINMUX_GIOA5_VALUE}
#define PINMUX_EXTCLKIN_PINMMR 2
#define PINMUX_EXTCLKIN_SHIFT 0
#define PINMUX_EXTCLKIN_VALUE 2
#define PINMUX_EXTCLKIN_PIN {PINMUX_EXTCLKIN_PINMMR, PINMUX_EXTCLKIN_SHIFT, PINMUX_EXTCLKIN_VALUE}
#define PINMUX_GIOA6_PINMMR 2
#define PINMUX_GIOA6_SHIFT 8
#define PINMUX_GIOA6_VALUE 1
#define PINMUX_GIOA6_PIN {PINMUX_GIOA6_PINMMR, PINMUX_GIOA6_SHIFT, PINMUX_GIOA6_VALUE}
#define PINMUX_SPI2NCS1_PINMMR 2
#define PINMUX_SPI2NCS1_SHIFT 8
#define PINMUX_SPI2NCS1_VALUE 2
#define PINMUX_SPI2NCS1_PIN {PINMUX_SPI2NCS1_PINMMR, PINMUX_SPI2NCS1_SHIFT, PINMUX_SPI2NCS1_VALUE}
#define PINMUX_N2HET31_PINMMR 2
#define PINMUX_N2HET31_SHIFT 8
#define PINMUX_N2HET31_VALUE 4
#define PINMUX_N2HET31_PIN {PINMUX_N2HET31_PINMMR, PINMUX_N2HET31_SHIFT, PINMUX_N2HET31_VALUE}
#define PINMUX_GIOA7_PINMMR 2
#define PINMUX_GIOA7_SHIFT 16
#define PINMUX_GIOA7_VALUE 1
#define PINMUX_GIOA7_PIN {PINMUX_GIOA7_PINMMR, PINMUX_GIOA7_SHIFT, PINMUX_GIOA7_VALUE}
#define PINMUX_N2HET29_PINMMR 2
#define PINMUX_N2HET29_SHIFT 16
#define PINMUX_N2HET29_VALUE 2
#define PINMUX_N2HET29_PIN {PINMUX_N2HET29_PINMMR, PINMUX_N2HET29_SHIFT, PINMUX_N2HET29_VALUE}
#define PINMUX_MIBSPI1NCS2_PINMMR 3
#define PINMUX_MIBSPI1NCS2_SHIFT 0
#define PINMUX_MIBSPI1NCS2_VALUE 1
#define PINMUX_MIBSPI1NCS2_PIN {PINMUX_MIBSPI1NCS2_PINMMR, PINMUX_MIBSPI1NCS2_SHIFT, PINMUX_MIBSPI1NCS2_VALUE}
#define PINMUX_N2HET20_PINMMR 3
#define PINMUX_N2HET20_SHIFT 0
#define PINMUX_N2HET20_VALUE 2
#define PINMUX_N2HET20_PIN {PINMUX_N2HET20_PINMMR, PINMUX_N2HET20_SHIFT, PINMUX_N2HET20_VALUE}
#define PINMUX_N2HET19_PINMMR 3
#define PINMUX_N2HET19_SHIFT 0
#define PINMUX_N2HET19_VALUE 4
#define PINMUX_N2HET19_PIN {PINMUX_N2HET19_PINMMR, PINMUX_N2HET19_SHIFT, PINMUX_N2HET19_VALUE}
#define PINMUX_SPI3CLK_PINMMR 3
#define PINMUX_SPI3CLK_SHIFT 16
#define PINMUX_SPI3CLK_VALUE 1
#define PINMUX_SPI3CLK_PIN {PINMUX_SPI3CLK_PINMMR, PINMUX_SPI3CLK_SHIFT, PINMUX_N2HET20_VALUE}
#define PINMUX_EQEPA_PINMMR 3
#define PINMUX_EQEPA_SHIFT 16
#define PINMUX_EQEPA_VALUE 2
#define PINMUX_EQEPA_PIN {PINMUX_EQEPA_PINMMR, PINMUX_EQEPA_SHIFT, PINMUX_EQEPA_VALUE}
#define PINMUX_SPI3NENA_PINMMR 3
#define PINMUX_SPI3NENA_SHIFT 24
#define PINMUX_SPI3NENA_VALUE 1
#define PINMUX_SPI3NENA_PIN {PINMUX_SPI3NENA_PINMMR, PINMUX_SPI3NENA_SHIFT, PINMUX_SPI3NENA_VALUE}
#define PINMUX_EQEPB_PINMMR 3
#define PINMUX_EQEPB_SHIFT 24
#define PINMUX_EQEPB_VALUE 2
#define PINMUX_EQEPB_PIN {PINMUX_EQEPB_PINMMR, PINMUX_EQEPB_SHIFT, PINMUX_EQEPB_VALUE}
#define PINMUX_SPI3NCS0_PINMMR 4
#define PINMUX_SPI3NCS0_SHIFT 0
#define PINMUX_SPI3NCS0_VALUE 1
#define PINMUX_SPI3NCS0_PIN {PINMUX_SPI3NCS0_PINMMR, PINMUX_SPI3NCS0_SHIFT, PINMUX_SPI3NCS0_VALUE}
#define PINMUX_EQEPI_PINMMR 4
#define PINMUX_EQEPI_SHIFT 0
#define PINMUX_EQEPI_VALUE 2
#define PINMUX_EQEPI_PIN {PINMUX_EQEPI_PINMMR, PINMUX_EQEPI_SHIFT, PINMUX_EQEPI_VALUE}
#define PINMUX_MIBSPI1NCS3_PINMMR 4
#define PINMUX_MIBSPI1NCS3_SHIFT 8
#define PINMUX_MIBSPI1NCS3_VALUE 1
#define PINMUX_MIBSPI1NCS3_PIN {PINMUX_MIBSPI1NCS3_PINMMR, PINMUX_MIBSPI1NCS3_SHIFT, PINMUX_MIBSPI1NCS3_VALUE}
#define PINMUX_N2HET26_PINMMR 4
#define PINMUX_N2HET26_SHIFT 8
#define PINMUX_N2HET26_VALUE 2
#define PINMUX_N2HET26_PIN {PINMUX_N2HET26_PINMMR, PINMUX_N2HET26_SHIFT, PINMUX_N2HET26_VALUE}
#define PINMUX_ADEVT_PINMMR 4
#define PINMUX_ADEVT_SHIFT 16
#define PINMUX_ADEVT_VALUE 1
#define PINMUX_ADEVT_PIN {PINMUX_ADEVT_PINMMR, PINMUX_ADEVT_SHIFT, PINMUX_ADEVT_VALUE}
#define PINMUX_N2HET28_PINMMR 4
#define PINMUX_N2HET28_SHIFT 16
#define PINMUX_N2HET28_VALUE 2
#define PINMUX_N2HET28_PIN {PINMUX_N2HET28_PINMMR, PINMUX_N2HET28_SHIFT, PINMUX_N2HET28_VALUE}
#define PINMUX_MIBSPI1NENA_PINMMR 5
#define PINMUX_MIBSPI1NENA_SHIFT 8
#define PINMUX_MIBSPI1NENA_VALUE 1
#define PINMUX_MIBSPI1NENA_PIN {PINMUX_MIBSPI1NENA_PINMMR, PINMUX_MIBSPI1NENA_SHIFT, PINMUX_MIBSPI1NENA_VALUE}
#define PINMUX_N2HET23_PINMMR 5
#define PINMUX_N2HET23_SHIFT 8
#define PINMUX_N2HET23_VALUE 2
#define PINMUX_N2HET23_PIN {PINMUX_N2HET23_PINMMR, PINMUX_N2HET23_SHIFT, PINMUX_N2HET23_VALUE}
#define PINMUX_N2HET30_PINMMR 5
#define PINMUX_N2HET30_SHIFT 8
#define PINMUX_N2HET30_VALUE 4
#define PINMUX_N2HET30_PIN {PINMUX_N2HET30_PINMMR, PINMUX_N2HET30_SHIFT, PINMUX_N2HET30_VALUE}
#define PINMUX_MIBSPI1NCS1_PINMMR 6
#define PINMUX_MIBSPI1NCS1_SHIFT 8
#define PINMUX_MIBSPI1NCS1_VALUE 1
#define PINMUX_MIBSPI1NCS1_PIN {PINMUX_MIBSPI1NCS1_PINMMR, PINMUX_MIBSPI1NCS1_SHIFT, PINMUX_MIBSPI1NCS1_VALUE}
#define PINMUX_EQEPS_PINMMR 6
#define PINMUX_EQEPS_SHIFT 8
#define PINMUX_EQEPS_VALUE 2
#define PINMUX_EQEPS_PIN {PINMUX_EQEPS_PINMMR, PINMUX_EQEPS_SHIFT, PINMUX_EQEPS_VALUE}
#define PINMUX_N2HET17_PINMMR 6
#define PINMUX_N2HET17_SHIFT 8
#define PINMUX_N2HET17_VALUE 4
#define PINMUX_N2HET17_PIN {PINMUX_N2HET17_PINMMR, PINMUX_N2HET17_SHIFT, PINMUX_N2HET17_VALUE}
#endif /* __ARCH_ARM_SRC_TMS570_CHIP_TMS570LS04X03X_PINMUX_H */

View File

@ -225,13 +225,13 @@ void arm_boot(void)
#ifdef CONFIG_TMS570_SELFTEST
/* Run a diagnostic check on the memory self-test controller. */
# warning Missing logic
/* Run PBIST on CPU RAM. */
# warning Missing logic
tms570_memtest_selftest();
/* Disable PBIST clocks and disable memory self-test mode */
# warning Missing logic
/* Run the memory selftest on CPU RAM. */
tms570_memtest_start(PBIST_RINFOL_ESRAM1_RAM)
ASSERT(tms570_memtest_complete() == 0);
#endif /* CONFIG_TMS570_SELFTEST */
/* Initialize CPU RAM. */
@ -244,11 +244,32 @@ void arm_boot(void)
#ifdef CONFIG_TMS570_SELFTEST
/* Perform PBIST on all dual-port memories */
#warning Missing logic
tms570_memtest_start(PBIST_RINFOL_VIM_RAM
#ifdef CONFIG_TMS570_DCAN1
| PBIST_RINFOL_DCAN1_RAM
#endif
#ifdef CONFIG_TMS570_DCAN2
| PBIST_RINFOL_DCAN2_RAM
#endif
#ifdef CONFIG_TMS570_MIBASPI1
| PBIST_RINFOL_MIBSPI1_RAM
#endif
#ifdef CONFIG_TMS570_MIBASPI1
| PBIST_RINFOL_MIBADC_RAM
#endif
#ifdef CONFIG_TMS570_N2HET
| PBIST_RINFOL_N2HET_RAM
| PBIST_RINFOL_HET_TU_RAM
#endif
);
/* Test the CPU ECC mechanism for RAM accesses. */
#warning Missing logic
/* Wait for the memory test to complete */
ASSERT(tms570_memtest_complete() == 0);
#endif /* CONFIG_TMS570_SELFTEST */
/* Release the MibSPI1 modules from local reset. */

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/samv7/tms570_start.h
* arch/arm/src/tms570/tms570_boot.h
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -33,8 +33,8 @@
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_SAMV7_SAM_START_H
#define __ARCH_ARM_SRC_SAMV7_SAM_START_H
#ifndef __ARCH_ARM_SRC_TMS570_SAM_BOOT_H
#define __ARCH_ARM_SRC_TMS570_SAM_BOOT_H
/************************************************************************************
* Included Files
@ -139,4 +139,4 @@ void tms570_board_initialize(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_SAMV7_SAM_START_H */
#endif /* __ARCH_ARM_SRC_TMS570_SAM_BOOT_H */

View File

@ -46,16 +46,32 @@
#include <nuttx/config.h>
#include <stdint.h>
#include <arch/board/board.h>
#include <assert.h>
#include "up_arch.h"
#include "chip/tms570_sys.h"
#include "chip/tms570_pcr.h"
#include "chip/tms570_flash.h"
#include "chip/tms570_iomm.h"
#include "chip/tms570_pinmux.h"
#include "tms570_selftest.h"
#include "tms570_clockconfig.h"
#include <arch/board/board.h>
/****************************************************************************
* Private Data
****************************************************************************/
static const struct tms570_pinmux_s g_pinmux_table[] =
{
BOARD_PINMUX_INITIALIZER
};
#define NPINMUX (sizeof(g_pinmux_table) / sizeof(struct tms570_pinmux_s))
/****************************************************************************
* Private Functions
****************************************************************************/
@ -208,6 +224,56 @@ static void tms570_peripheral_initialize(void)
putreg32(clkcntl, TMS570_SYS_CLKCNTL);
}
/****************************************************************************
* Name: tms570_pin_multiplex
*
* Description:
* Configure the field for a single pin in a PINMMR register
*
****************************************************************************/
static void tms570_pin_multiplex(FAR const struct tms570_pinmux_s *pinmux)
{
uintptr_t regaddr;
uint32_t regval;
regaddr = TMS570_IOMM_PINMMR(pinmux->mmrndx);
regval = getreg32(regaddr);
regval &= ~(0xff << pinmux->shift);
regval |= ((uint32_t)(pinmux->value) << pinmux->shift);
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: tms570_io_multiplex
*
* Description:
* Configure the all pins in the board-provided pinmux table.
*
****************************************************************************/
static void tms570_io_multiplex(void)
{
int i;
/* Enable access to pin multiplexing registers */
putreg32(IOMM_KICK0_UNLOCK, TMS570_IOMM_KICK0);
putreg32(IOMM_KICK1_UNLOCK, TMS570_IOMM_KICK1);
/* Configure each pin selected by the board-specific logic */
for (i = 0; i < NPINMUX; i++)
{
tms570_pin_multiplex(&g_pinmux_table[i]);
}
/* Disable access to pin multiplexing registers */
putreg32(IOMM_KICK0_LOCK, TMS570_IOMM_KICK0);
putreg32(IOMM_KICK1_LOCK, TMS570_IOMM_KICK1);
}
/****************************************************************************
* Name: tms570_lpo_trim
*
@ -445,11 +511,9 @@ void tms570_clockconfig(void)
#ifdef CONFIG_TMS570_SELFTEST
/* Run eFuse controller start-up checks and start eFuse controller ECC
* self-test. This includes a check for the eFuse controller error
* outputs to be stuck-at-zero.
*/
* self-test.*/
# warning Missing Logic
tms570_efc_selftest_start();
#endif /* CONFIG_TMS570_SELFTEST */
/* Enable clocks to peripherals and release peripheral reset */
@ -457,12 +521,13 @@ void tms570_clockconfig(void)
tms570_peripheral_initialize();
/* Configure device-level multiplexing and I/O multiplexing */
#warning Missing Logic
tms570_io_multiplex();
#ifdef CONFIG_TMS570_SELFTEST
/* Wait for eFuse controller self-test to complete and check results */
# warning Missing Logic
ASSERT(tms570_efc_selftest_complete() == 0);
#endif
/* Set up flash address and data wait states. */

View File

@ -1,4 +1,4 @@
/************************************************************************************
/****************************************************************************
* arch/arm/src/tms570/tms570_clockconfig.h
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
@ -31,35 +31,23 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
****************************************************************************/
#ifndef __ARCH_ARM_SRC_TMS570_TMS570_CLOCKCONFIG_H
#define __ARCH_ARM_SRC_TMS570_TMS570_CLOCKCONFIG_H
/************************************************************************************
/****************************************************************************
* Included Files
************************************************************************************/
****************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Inline Functions
************************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
/************************************************************************************
* Public Data
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
@ -69,11 +57,11 @@ extern "C"
#define EXTERN extern
#endif
/************************************************************************************
/****************************************************************************
* Public Function Prototypes
************************************************************************************/
****************************************************************************/
/************************************************************************************
/****************************************************************************
* Name: tms570_clockconfig
*
* Description:
@ -81,7 +69,7 @@ extern "C"
* put the SoC in a usable state. This includes, but is not limited to, the
* initialization of clocking using the settings in the board.h header file.
*
************************************************************************************/
****************************************************************************/
void tms570_clockconfig(void);

View File

@ -40,6 +40,8 @@
#include <nuttx/config.h>
#include <stdint.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/irq.h>
@ -49,6 +51,9 @@
#include "up_arch.h"
#include "up_internal.h"
#include "chip/tms570_vim.h"
#include "tms570_irq.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -63,42 +68,113 @@
volatile uint32_t *current_regs;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: tms570_error_handler
****************************************************************************/
static void tms570_error_handler(void)
{
PANIC();
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_irqinitialize
* The device supports three different possibilities for software to handle
* interrupts:
*
* 1. Index interrupts mode (compatible with TMS470R1x legacy code),
* 2. Register vectored interrupts (automatically provide vector address
* to application)
* 3. Hardware vectored interrupts (automatically dispatch to ISR, IRQ
* only)
*
* Only the indexed mode is supported here: After the interrupt is received
* by the CPU, the CPU branches to 0x18 (IRQ) or 0x1C (FIQ) to execute the
* main ISR. The main ISR routine reads the offset register (IRQINDEX,
* FIQINDEX) to determine the source of the interrupt.
*
* To use mode 2), it would only be necessary to initialize the VIM_RAM.
* To use mode 3), it would be necessary to initialize the VIM_RAM and also
* to set the vector enable (VE) bit in the CP15 R1 register. This bit is
* zero on reset so that the default state after reset is backward
* compatible to earlier ARM CPU.
*
****************************************************************************/
void up_irqinitialize(void)
{
/* Disable all interrupts. */
#warning Missing logic
FAR uintptr_t *vimram;
int i;
/* Colorize the interrupt stack for debug purposes */
#if defined(CONFIG_STACK_COLORATION) && CONFIG_ARCH_INTERRUPTSTACK > 3
{
size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size),
intstack_size);
}
size_t intstack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
up_stack_color((FAR void *)((uintptr_t)&g_intstackbase - intstack_size),
intstack_size);
#endif
/* Set all interrupts to the default priority */
#warning Missing logic
/* Initialize VIM RAM vectors. These vectors are not used in the current
* interrupt handler logic.
*/
vimram = (FAR uintptr_t *)TMS570_VIMRAM_BASE;
for (i = 0; i < (TMS570_IRQ_NCHANNELS + 1); i++)
{
*vimram++ = (uintptr_t)tms570_error_handler;
}
/* Set Fall-Back Address Parity Error Register (also not used) */
putreg32((uint32_t)tms570_error_handler, TMS570_VIM_FBPARERR);
/* Assign all channels to IRQs */
putreg32(0, TMS570_VIM_FIRQPR0);
putreg32(0, TMS570_VIM_FIRQPR1);
putreg32(0, TMS570_VIM_FIRQPR2);
#ifdef TMS570_VIM_FIRQPR3
putreg32(0, TMS570_VIM_FIRQPR3);
#endif
/* Disable all interrupts */
putreg32(0xfffffffc, TMS570_VIM_REQENACLR0);
putreg32(0xffffffff, TMS570_VIM_REQENACLR1);
putreg32(0xffffffff, TMS570_VIM_REQENACLR2);
#ifdef TMS570_VIM_REQENACLR3
putreg32(0xffffffff, TMS570_VIM_REQENACLR3);
#endif
/* currents_regs is non-NULL only while processing an interrupt */
current_regs = NULL;
#ifdef CONFIG_ARMV7R_HAVE_DECODEFIQ
/* By default, interrupt CHAN0 is mapped to ESM (Error Signal Module)
* high level interrupt and CHAN1 is reserved for other NMI. For safety
* reasons, these two channels are mapped to FIQ only and can NOT be
* disabled through ENABLE registers.
*/
#warning Missing Logic
#endif
#ifndef CONFIG_SUPPRESS_INTERRUPTS
#ifdef CONFIG_TMS570_GPIO_IRQ
/* Initialize logic to support a second level of interrupt decoding for
* GPIO pins.
*/
#ifdef CONFIG_TMS570_GPIO_IRQ
tms570_gpioirqinitialize();
#endif
@ -109,31 +185,230 @@ void up_irqinitialize(void)
}
/****************************************************************************
* Name: up_disable_irq
* Name: tms570_vim_channel
*
* Description:
* Disable the IRQ specified by 'irq'
* Allocate a VIM channel and assign it to the 'request'.
*
* Input Parameters:
* request - The interrupt request to be mapped to a channel
*
* Returned Value:
* One sucess, the allocated channel number is returned. A negated errno
* value is returned on any failure.
*
****************************************************************************/
void up_disable_irq(int irq)
int tms570_vim_channel(int request)
{
#warning Missing logic
return -ENOSYS;
}
/****************************************************************************
* Name: arm_decodeirq
*
* Description:
* This function is called from the IRQ vector handler in arm_vectors.S.
* At this point, the interrupt has been taken and the registers have
* been saved on the stack. This function simply needs to determine the
* the irq number of the interrupt and then to call arm_doirq to dispatch
* the interrupt.
*
* Input parameters:
* regs - A pointer to the register save area on the stack.
*
****************************************************************************/
uint32_t *arm_decodeirq(uint32_t *regs)
{
int vector;
/* Check for a VRAM parity error. This is not to critical in this
* implementatin since VIM RAM is not used.
*/
#warning Missing logic
/* Get the interrupting vector number from the IRQINDEX register. Zero,
* the "phantom" vector will returned.
*/
vector = getreg32(TMS570_VIM_IRQINDEX) & VIM_IRQINDEX_MASK;
if (vector > 0)
{
/* Dispatch the interrupt. NOTE that the IRQ number is the vector
* number offset by one to skip over the "phantom" vector.
*/
regs = arm_doirq(vector - 1, regs);
}
/* Acknowledge interrupt */
#warning Verify not needed
return regs;
}
/****************************************************************************
* Name: arm_decodefiq
*
* Description:
* This function is called from the FIQ vector handler in arm_vectors.S.
* At this point, the interrupt has been taken and the registers have
* been saved on the stack. This function simply needs to determine the
* the irq number of the interrupt and then to call arm_doirq to dispatch
* the interrupt.
*
* Input parameters:
* regs - A pointer to the register save area on the stack.
*
****************************************************************************/
#ifdef CONFIG_ARMV7R_HAVE_DECODEFIQ
uint32_t *arm_decodefiq(FAR uint32_t *regs)
{
int vector;
/* Check for a VRAM parity error. This is not to critical in this
* implementatin since VIM RAM is not used.
*/
#warning Missing logic
/* Get the interrupting vector number from the FIQINDEX register. Zero,
* the "phantom" vector will returned.
*/
vector = getreg32(TMS570_VIM_FIQINDEX) & VIM_FIQINDEX_MASK;
if (vector > 0)
{
/* Dispatch the interrupt. NOTE that the IRQ number is the vector
* number offset by one to skip over the "phantom" vector.
*/
regs = arm_doirq(vector - 1, regs)
}
/* Acknowledge interrupt */
#warning Verify not needed
return regs;
}
#endif
/****************************************************************************
* Name: up_disable_irq
*
* Description:
* Disable the IRQ or FIQ specified by 'channel'
*
****************************************************************************/
void up_disable_irq(int channel)
{
uintptr_t regaddr;
uint32_t regval;
uint32_t bitmask;
unsigned int regndx;
DEBUGASSERT(channel >= 0 && channel < TMS570_IRQ_NCHANNELS)
/* Offset to account for the "phantom" vector */
channel++;
regndx = VIM_REGNDX(channel);
channel = VIM_REGBIT(channel);
bitmask = (1 << channel);
/* Disable the IRQ/FIQ by setting the corresponding REQENACLR bit. */
regaddr = TMS570_VIM_REQENACLR(regndx);
regval = getreg32(regaddr);
regaddr |= bitmask;
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: up_enable_irq
*
* Description:
* Enable the IRQ specified by 'irq'
* Enable the IRQ specified by 'channel'
*
****************************************************************************/
void up_enable_irq(int irq)
void up_enable_irq(int channel)
{
#warning Missing logic
uintptr_t regaddr;
uint32_t regval;
uint32_t bitmask;
unsigned int regndx;
DEBUGASSERT(channel >= 0 && channel < TMS570_IRQ_NCHANNELS)
/* Offset to account for the "phantom" vector */
channel++;
regndx = VIM_REGNDX(channel);
channel = VIM_REGBIT(channel);
bitmask = (1 << channel);
#ifdef CONFIG_ARMV7R_HAVE_DECODEFIQ
/* Select IRQ (vs FIQ) by clearing the corresponding FIRQPR bit */
regaddr = TMS570_VIM_FIRQPR(regndx);
regval = getreg32(regaddr);
regaddr &= ~bitmask;
putreg32(regval, regaddr);
#endif
/* Enable the IRQ by setting the corresponding REQENASET bit. */
regaddr = TMS570_VIM_REQENASET(regndx);
regval = getreg32(regaddr);
regaddr |= bitmask;
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: up_enable_fiq
*
* Description:
* Enable the FIQ specified by 'channel'
*
****************************************************************************/
#ifdef CONFIG_ARMV7R_HAVE_DECODEFIQ
void up_enable_fiq(int channel)
{
uintptr_t regaddr;
uint32_t regval;
uint32_t bitmask;
unsigned int regndx;
DEBUGASSERT(channel >= 0 && channel < TMS570_IRQ_NCHANNELS)
/* Offset to account for the "phantom" vector */
channel++;
regndx = VIM_REGNDX(channel);
channel = VIM_REGBIT(channel);
bitmask = (1 << channel);
/* Select FIQ (vs IRQ) by setting the corresponding FIRQPR bit */
regaddr = TMS570_VIM_FIRQPR(regndx);
regval = getreg32(regaddr);
regaddr &= ~bitmask;
putreg32(regval, regaddr);
/* Enable the FIQ by setting the corresponding REQENASET bit. */
regaddr = TMS570_VIM_REQENASET(regndx);
regval = getreg32(regaddr);
regaddr |= bitmask;
putreg32(regval, regaddr);
}
#endif
/****************************************************************************
* Name: up_ack_irq
*
@ -159,7 +434,7 @@ void up_ack_irq(int irq)
****************************************************************************/
#ifdef CONFIG_ARCH_IRQPRIO
int up_prioritize_irq(int irq, int priority)
int up_prioritize_irq(int channel, int priority)
{
#warning Missing logic
}

View File

@ -0,0 +1,99 @@
/****************************************************************************
* arch/arm/src/tms570/tms570_irq.h
*
* Copyright (C) 2015 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_ARM_SRC_TMS570_SAM_IRQ_H
#define __ARCH_ARM_SRC_TMS570_SAM_IRQ_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: tms570_vim_channel
*
* Description:
* Allocate a VIM channel and assign it to the 'request'.
*
* Input Parameters:
* request - The interrupt request to be mapped to a channel
*
* Returned Value:
* One sucess, the allocated channel number is returned. A negated errno
* value is returned on any failure.
*
****************************************************************************/
int tms570_vim_channel(int request);
/****************************************************************************
* Name: up_enable_fiq
*
* Description:
* Enable the FIQ specified by 'channel'
*
****************************************************************************/
#ifdef CONFIG_ARMV7R_HAVE_DECODEFIQ
void up_enable_fiq(int channel);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_TMS570_SAM_IRQ_H */

View File

@ -0,0 +1,147 @@
/****************************************************************************
* arch/arm/src/tms570/tms570_selftest.c
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Most logic in this file was leveraged from TI's Project0 which has a
* compatible BSD license:
*
* Copyright (c) 2012, Texas Instruments Incorporated
* All rights reserved.
*
* 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 "tms570_selftest.h"
#ifdef CONFIG_TMS570_SELFTEST
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: tms570_memtest_selftest
*
* Description:
* Run a diagnostic check on the memory self-test controller.
*
* This function chooses a RAM test algorithm and runs it on an on-chip
* ROM. The memory self-test is expected to fail. The function ensures
* that the PBIST controller is capable of detecting and indicating a
* memory self-test failure.
*
****************************************************************************/
void tms570_memtest_selftest(void)
{
#warning Missing Logic
}
/****************************************************************************
* Name: tms570_memtest_start
*
* Description:
* Start the memory test on the selecte set of RAMs. This test does not
* return until the memory test is completed.
*
* Input Paramters:
* rinfol - The OR of each RAM grouping bit. See the PBIST_RINFOL*
* definitions in chip/tms570_pbist.h
*
****************************************************************************/
void tms570_memtest_start(uint32_t rinfol)
{
#warning Missing Logic
}
/****************************************************************************
* Name: tms570_memtest_complete
*
* Description:
* Wait for memory self-test to complete and return the result.
*
* Returned Value:
* Zero (OK) if the test passed; A negated errno value is returned on
* any failure.
*
****************************************************************************/
int tms570_memtest_complete(void)
{
#warning Missing Logic
return 0;
}
/****************************************************************************
* Name: tms570_efc_selftest_start
*
* Description:
* Run eFuse controller start-up checks and start eFuse controller ECC
* self-test. This includes a check for the eFuse controller error
* outputs to be stuck-at-zero.
*
****************************************************************************/
void tms570_efc_selftest_start(void)
{
#warning Missing Logic
}
/****************************************************************************
* Name: tms570_efc_selftest_complete
*
* Description:
* Wait for eFuse controller self-test to complete and return the result.
*
* Returned Value:
* Zero (OK) if the test passed; A negated errno value is returned on
* any failure.
*
****************************************************************************/
int tms570_efc_selftest_complete(void)
{
#warning Missing Logic
return 0;
}
#endif /* CONFIG_TMS570_SELFTEST */

View File

@ -0,0 +1,146 @@
/****************************************************************************
* arch/arm/src/tms570/tms570_selftest.h
*
* Copyright (C) 2015 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_ARM_SRC_TMS570_TMS570_SELFTEST_H
#define __ARCH_ARM_SRC_TMS570_TMS570_SELFTEST_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#ifdef CONFIG_TMS570_SELFTEST
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: tms570_memtest_selftest
*
* Description:
* Run a diagnostic check on the memory self-test controller.
*
* This function chooses a RAM test algorithm and runs it on an on-chip
* ROM. The memory self-test is expected to fail. The function ensures
* that the PBIST controller is capable of detecting and indicating a
* memory self-test failure.
*
****************************************************************************/
void tms570_memtest_selftest(void);
/****************************************************************************
* Name: tms570_memtest_start
*
* Description:
* Start the memory test on the selected set of RAMs.
*
* Input Paramters:
* rinfol - The OR of each RAM grouping bit. See the PBIST_RINFOL*
* definitions in chip/tms570_pbist.h
*
****************************************************************************/
void tms570_memtest_start(uint32_t rinfol);
/****************************************************************************
* Name: tms570_memtest_complete
*
* Description:
* Wait for memory self-test to complete and return the result.
*
* Returned Value:
* Zero (OK) if the test passed; A negated errno value is returned on
* any failure.
*
****************************************************************************/
int tms570_memtest_complete(void);
/****************************************************************************
* Name: tms570_efc_selftest_start
*
* Description:
* Run eFuse controller start-up checks and start eFuse controller ECC
* self-test. This includes a check for the eFuse controller error
* outputs to be stuck-at-zero.
*
****************************************************************************/
void tms570_efc_selftest_start(void);
/****************************************************************************
* Name: tms570_efc_selftest_complete
*
* Description:
* Wait for eFuse controller self-test to complete and return the result.
*
* Returned Value:
* Zero (OK) if the test passed; A negated errno value is returned on
* any failure.
*
****************************************************************************/
int tms570_efc_selftest_complete(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* CONFIG_TMS570_SELFTEST */
#endif /* __ARCH_ARM_SRC_TMS570_TMS570_SELFTEST_H */