Skip to content
/****************************************************************************
* arch/arm/src/lc823450/chip/lc823450_vectors.h
*
* Copyright (C) 2014-2017 Sony Corporation. All rights reserved.
* Copyright 2014,2017 Sony Video & Sound Products Inc.
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
*
......
/****************************************************************************
* arch/arm/src/lc823450/lc823450_wdt.c
*
* Copyright (C) 2014-2017 Sony Corporation. All rights reserved.
* Copyright 2014,2015,2017 Sony Video & Sound Products Inc.
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
* Author: Nobutaka Toyoshima <Nobutaka.Toyoshima@jp.sony.com>
* Author: Masatoshi Tateishi <Masatoshi.Tateishi@jp.sony.com>
......
/****************************************************************************
* arch/arm/src/lc823450/lc823450_wdt.h
*
* Copyright (C) 2014-2017 Sony Corporation. All rights reserved.
* Copyright 2014,2017 Sony Video & Sound Products Inc.
* Author: Masayuki Ishikawa <Masayuki.Ishikawa@jp.sony.com>
* Author: Nobutaka Toyoshima <Nobutaka.Toyoshima@jp.sony.com>
*
......
......@@ -2381,26 +2381,38 @@ if STM32_HRTIM1
config STM32_HRTIM_MASTER
bool "HRTIM MASTER"
default n
---help---
Enable HRTIM Master Timer
config STM32_HRTIM_TIMA
bool "HRTIM TIMA"
default n
---help---
Enable HRTIM Timer A
config STM32_HRTIM_TIMB
bool "HRTIM TIMB"
default n
---help---
Enable HRTIM Timer B
config STM32_HRTIM_TIMC
bool "HRTIM TIMC"
default n
---help---
Enable HRTIM Timer C
config STM32_HRTIM_TIMD
bool "HRTIM TIMD"
default n
---help---
Enable HRTIM Timer D
config STM32_HRTIM_TIME
bool "HRTIM TIME"
default n
---help---
Enable HRTIM Timer E
endif # STM32_HRTIM
......@@ -5853,10 +5865,15 @@ if STM32_HRTIM1
config STM32_HRTIM_DISABLE_CHARDRV
bool "HRTIM Disable Character Driver"
default n
---help---
In most cases we do not need HRTIM Character Driver, so we can disable it
and save some memory.
menuconfig STM32_HRTIM_ADC
bool "HRTIM ADC Configuration"
bool "HRTIM ADC Triggering"
default n
---help---
Enable HRTIM ADC Triggering support.
if STM32_HRTIM_ADC
......@@ -5897,33 +5914,54 @@ endif # STM32_HRTIM_ADC
config STM32_HRTIM_DAC
bool "HRTIM DAC Triggering"
default n
---help---
Enable HRTIM DAC Triggering support.
config STM32_HRTIM_PWM
bool "HRTIM PWM Outputs"
default n
---help---
Enable HRTIM PWM Outputs support.
config STM32_HRTIM_CAP
bool "HRTIM Capture"
default n
---help---
Enable HRTIM Capture support.
config STM32_HRTIM_INTERRUPTS
bool "HRTIM Interrupts"
default n
---help---
Enable HRTIM Interrupts support.
config STM32_HRTIM_BURST
bool "HRTIM Burst Mode"
depends on STM32_HRTIM_PWM
default n
---help---
Enable HRTIM Burst Mode support for PWM outputs.
config STM32_HRTIM_DEADTIME
bool "HRTIM Dead-time"
depends on STM32_HRTIM_PWM
default n
---help---
Enable HRTIM Deadtime support for PWM outputs.
config STM32_HRTIM_PUSHPULL
bool "HRTIM push-pull mode"
bool "HRTIM Push-Pull Mode"
depends on STM32_HRTIM_PWM
default n
---help---
Enable HRTIM Push-Pull Mode support for PWM outputs.
config STM32_HRTIM_CHOPPER
bool "HRTIM Chopper"
depends on STM32_HRTIM_PWM
default n
---help---
Enable HRTIM Chopper Mode for PWM outputs.
config STM32_HRTIM_DMA
bool "HRTIM DMA"
......@@ -5933,11 +5971,6 @@ config STM32_HRTIM_DMABURST
bool "HRTIM DMA Burst"
default n
config STM32_HRTIM_CHOPPER
bool "HRTIM Chopper"
depends on STM32_HRTIM_PWM
default n
config STM32_HRTIM_AUTODELAY
bool "HRTIM Autodelay"
depends on STM32_HRTIM_PWM
......@@ -5946,6 +5979,8 @@ config STM32_HRTIM_AUTODELAY
menuconfig STM32_HRTIM_EVENTS
bool "HRTIM Events Configuration"
default n
---help---
Enable HRTIM Events support.
if STM32_HRTIM_EVENTS
......@@ -5994,6 +6029,8 @@ endif # STM32_HRTIM_EVENTS
menuconfig STM32_HRTIM_FAULTS
bool "HRTIM Faults Configuration"
default n
---help---
Enable HRTIM Faults support.
if STM32_HRTIM_FAULTS
......@@ -6018,6 +6055,11 @@ endif # STM32_HRTIM_FAULTS
config STM32_HRTIM_CLK_FROM_PLL
bool "HRTIM Clock from PLL"
default n
---help---
Set PLL as the clock source for HRTIM.
This configuration requires the following conditions:
1) system clock is PLL,
2) SYSCLK and PCLK2 ratio must be 1 o 2.
menu "HRTIM Master Configuration"
depends on STM32_HRTIM_MASTER
......@@ -6446,6 +6488,22 @@ config STM32_ADC4_DMA
DMA transfer, which is necessary if multiple channels are read
or if very high trigger frequencies are used.
config STM32_ADC1_INJECTED
bool "ADC1 INJECTED"
depends on STM32_ADC1 && STM32_STM32F33XX
default n
---help---
Support for ADC1 injected channels.
Only for STM32_STM32F33XX at this moment.
config STM32_ADC2_INJECTED
bool "ADC2 INJECTED"
depends on STM32_ADC2 && STM32_STM32F33XX
default n
---help---
Support for ADC2 injected channels.
Only for STM32_STM32F33XX at this moment.
endmenu
menu "SDADC Configuration"
......
......@@ -1042,13 +1042,13 @@
/* Common Control Register 1 */
#define HRTIM_CR1_MUDIS (1 << 0) /* Bit 0 */
#define HRTIM_CR1_TAUDIS (1 << 1) /* Bit 1 */
#define HRTIM_CR1_TBUDIS (1 << 2) /* Bit 2 */
#define HRTIM_CR1_TCUDIS (1 << 3) /* Bit 3 */
#define HRTIM_CR1_TDUDIS (1 << 4) /* Bit 4 */
#define HRTIM_CR1_TEUDIS (1 << 5) /* Bit 5 */
#define HRTIM_CR1_AD1USRC_SHIFT 16 /* Bits 16-18 */
#define HRTIM_CR1_MUDIS (1 << 0) /* Bit 0: Master Update Disable */
#define HRTIM_CR1_TAUDIS (1 << 1) /* Bit 1: Timer A Update Disable */
#define HRTIM_CR1_TBUDIS (1 << 2) /* Bit 2: Timer B Update Disable */
#define HRTIM_CR1_TCUDIS (1 << 3) /* Bit 3: Timer C Update Disable */
#define HRTIM_CR1_TDUDIS (1 << 4) /* Bit 4: Timer D Update Disable */
#define HRTIM_CR1_TEUDIS (1 << 5) /* Bit 5: Timer E Update Disable */
#define HRTIM_CR1_AD1USRC_SHIFT 16 /* Bits 16-18: ADC Trigger 1 Update Source */
#define HRTIM_CR1_AD1USRC_MASK (7 << HRTIM_CR1_AD1USRC_SHIFT)
# define HRTIM_CR1_AD1USRC_MT (0 << HRTIM_CR1_AD1USRC_SHIFT) /* 000: Mater Timer */
# define HRTIM_CR1_AD1USRC_TA (1 << HRTIM_CR1_AD1USRC_SHIFT) /* 001: Timer A */
......@@ -1056,7 +1056,7 @@
# define HRTIM_CR1_AD1USRC_TC (3 << HRTIM_CR1_AD1USRC_SHIFT) /* 011: Timer C */
# define HRTIM_CR1_AD1USRC_TD (4 << HRTIM_CR1_AD1USRC_SHIFT) /* 100: Timer D */
# define HRTIM_CR1_AD1USRC_TE (5 << HRTIM_CR1_AD1USRC_SHIFT) /* 101: Timer A */
#define HRTIM_CR1_AD2USRC_SHIFT 19 /* Bits 19-21 */
#define HRTIM_CR1_AD2USRC_SHIFT 19 /* Bits 19-21: ADC Trigger 2 Update Source */
#define HRTIM_CR1_AD2USRC_MASK (7 << HRTIM_CR1_AD2USRC_SHIFT)
# define HRTIM_CR1_AD2USRC_MT (0 << HRTIM_CR1_AD2USRC_SHIFT) /* 000: Mater Timer */
# define HRTIM_CR1_AD2USRC_TA (1 << HRTIM_CR1_AD2USRC_SHIFT) /* 001: Timer A */
......@@ -1064,7 +1064,7 @@
# define HRTIM_CR1_AD2USRC_TC (3 << HRTIM_CR1_AD2USRC_SHIFT) /* 011: Timer C */
# define HRTIM_CR1_AD2USRC_TD (4 << HRTIM_CR1_AD2USRC_SHIFT) /* 100: Timer D */
# define HRTIM_CR1_AD2USRC_TE (5 << HRTIM_CR1_AD2USRC_SHIFT) /* 101: Timer A */
#define HRTIM_CR1_AD3USRC_SHIFT 22 /* Bits 22-24 */
#define HRTIM_CR1_AD3USRC_SHIFT 22 /* Bits 22-24: ADC Trigger 3 Update Source */
#define HRTIM_CR1_AD3USRC_MASK (7 << HRTIM_CR1_AD3USRC_SHIFT)
# define HRTIM_CR1_AD3USRC_MT (0 << HRTIM_CR1_AD3USRC_SHIFT) /* 000: Mater Timer */
# define HRTIM_CR1_AD3USRC_TA (1 << HRTIM_CR1_AD3USRC_SHIFT) /* 001: Timer A */
......@@ -1072,7 +1072,7 @@
# define HRTIM_CR1_AD3USRC_TC (3 << HRTIM_CR1_AD3USRC_SHIFT) /* 011: Timer C */
# define HRTIM_CR1_AD3USRC_TD (4 << HRTIM_CR1_AD3USRC_SHIFT) /* 100: Timer D */
# define HRTIM_CR1_AD3USRC_TE (5 << HRTIM_CR1_AD3USRC_SHIFT) /* 101: Timer A */
#define HRTIM_CR1_AD4USRC_SHIFT 25 /* Bits 25-27 */
#define HRTIM_CR1_AD4USRC_SHIFT 25 /* Bits 25-27: ADC Trigger 4 Update Source */
#define HRTIM_CR1_AD4USRC_MASK (7 << HRTIM_CR1_AD4USRC_SHIFT)
# define HRTIM_CR1_AD4USRC_MT (0 << HRTIM_CR1_AD4USRC_SHIFT) /* 000: Mater Timer */
# define HRTIM_CR1_AD4USRC_TA (1 << HRTIM_CR1_AD4USRC_SHIFT) /* 001: Timer A */
......
......@@ -981,15 +981,12 @@ static int stm32_1wire_isr(int irq, void *context, void *arg)
stm32_1wire_send(priv, READ_TX);
break;
case ONEWIRETASK_WRITEBIT:
*priv->byte = 0;
priv->msgs = NULL;
priv->result = OK;
nxsem_post(&priv->sem_isr);
break;
case ONEWIRETASK_READBIT:
*priv->byte = (dr == READ_RX1) ? 1 : 0;
/* Fall through */
case ONEWIRETASK_WRITEBIT:
priv->msgs = NULL;
priv->result = OK;
nxsem_post(&priv->sem_isr);
......
/****************************************************************************
* arch/arm/src/stm32/stm32_hrtim.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Copyright (C) 2017-2018 Gregory Nutt. All rights reserved.
* Author: Mateusz Szafoni <raiden00@railab.me>
*
* Redistribution and use in source and binary forms, with or without
......@@ -57,8 +57,6 @@
#if defined(CONFIG_STM32_STM32F33XX)
#warning "HRTIM UNDER DEVELOPMENT !"
#if defined(CONFIG_STM32_HRTIM_TIMA_PWM) || defined(CONFIG_STM32_HRTIM_TIMA_DAC) || \
defined(CONFIG_STM32_HRTIM_TIMA_CAP) || defined(CONFIG_STM32_HRTIM_TIMA_IRQ) || \
defined(CONFIG_STM32_HRTIM_TIMA_DT) || defined(CONFIG_STM32_HRTIM_TIMA_CHOP)
......@@ -231,11 +229,6 @@
/* HRTIM default configuration **********************************************/
#ifndef HRTIM_MASTER_PRESCALER
# warning "HRTIM_MASTER_PRESCALER is not set. Set the default value HRTIM_PRESCALER_2"
# define HRTIM_MASTER_PRESCALER HRTIM_PRESCALER_2
#endif
#if defined(CONFIG_STM32_HRTIM_MASTER) && !defined(HRTIM_MASTER_MODE)
# warning "HRTIM_MASTER_MODE is not set. Set the default value 0"
# define HRTIM_MASTER_MODE 0
......@@ -3604,7 +3597,46 @@ errout:
static uint16_t hrtim_deadtime_get(FAR struct hrtim_dev_s *dev, uint8_t timer,
uint8_t dt)
{
#warning missing logic
FAR struct stm32_hrtim_s *priv = (FAR struct stm32_hrtim_s *)dev->hd_priv;
uint16_t regval = 0;
uint32_t shift = 0;
uint32_t mask = 0;
/* Get shift value */
switch (dt)
{
case HRTIM_DT_EDGE_RISING:
{
shift = HRTIM_TIMDT_DTR_SHIFT;
mask = HRTIM_TIMDT_DTR_MASK;
break;
}
case HRTIM_DT_EDGE_FALLING:
{
shift = HRTIM_TIMDT_DTF_SHIFT;
mask = HRTIM_TIMDT_DTF_MASK;
break;
}
default:
{
regval = 0;
goto errout;
}
}
/* Get Deadtime Register */
regval = hrtim_tim_getreg(priv, timer, STM32_HRTIM_TIM_DTR_OFFSET);
/* Get Deadtime value */
regval = (regval & mask) >> shift;
errout:
return regval;
}
/****************************************************************************
......
......@@ -212,6 +212,8 @@
(hrtim)->hd_ops->cmp_update(hrtim, tim, index, cmp)
#define HRTIM_PER_SET(hrtim, tim, per) \
(hrtim)->hd_ops->per_update(hrtim, tim, per)
#define HRTIM_REP_SET(hrtim, tim, per) \
(hrtim)->hd_ops->rep_update(hrtim, tim, per)
#define HRTIM_PER_GET(hrtim, tim) \
(hrtim)->hd_ops->per_get(hrtim, tim)
#define HRTIM_FCLK_GET(hrtim, tim) \
......
......@@ -660,6 +660,18 @@ static void stm32_stdclockconfig(void)
#endif
#if defined(CONFIG_RTC_LSECLOCK)
/* Normally peripheral clocks are enabled later in bootup, but we need
* clock on PWR *now* as without this setting registers that enable LSE
* won't work.
*
* NOTE: In this configuration, we can assume the CONFIG_STM32_PWR has
* been selected.
*/
regval = getreg32(STM32_RCC_APB1ENR);
regval |= RCC_APB1ENR_PWREN;
putreg32(regval, STM32_RCC_APB1ENR);
/* Low speed external clock source LSE
*
* TODO: There is another case where the LSE needs to
......
......@@ -119,6 +119,10 @@
# define ADC2_HAVE_JEXTSEL
#endif
#if defined(CONFIG_STM32_ADC_NOIRQ) && defined(ADC_HAVE_DMA)
# error "ADC DMA support requires common ADC interrupts"
#endif
/* RCC reset ****************************************************************/
#define STM32_RCC_RSTR STM32_RCC_AHBRSTR
......@@ -162,10 +166,13 @@
*/
#define ADC_MAX_CHANNELS_DMA 16
#define ADC_MAX_CHANNELS_NOIRQ 16
#define ADC_MAX_CHANNELS_NODMA 1
#ifdef ADC_HAVE_DMA
#if defined(ADC_HAVE_DMA)
# define ADC_REG_MAX_SAMPLES ADC_MAX_CHANNELS_DMA
#elif defined(CONFIG_STM32_ADC_NOIRQ)
# define ADC_REG_MAX_SAMPLES ADC_MAX_CHANNELS_NOIRQ
#else
# define ADC_REG_MAX_SAMPLES ADC_MAX_CHANNELS_NODMA
#endif
......@@ -1911,7 +1918,7 @@ static uint32_t adc_sqrbits(FAR struct stm32_dev_s *priv, int first, int last,
i < priv->rnchannels && i < last;
i++, offset += ADC_SQ_OFFSET)
{
bits |= (uint32_t)priv->r_chanlist[i] << offset;
bits |= ((uint32_t)priv->r_chanlist[i]) << offset;
}
return bits;
......
......@@ -72,7 +72,7 @@
# define STM32_GPIOA_PUPDR (STM32_GPIOA_BASE+STM32_GPIO_PUPDR_OFFSET)
# define STM32_GPIOA_IDR (STM32_GPIOA_BASE+STM32_GPIO_IDR_OFFSET)
# define STM32_GPIOA_ODR (STM32_GPIOA_BASE+STM32_GPIO_ODR_OFFSET)
# define STM32_GPIOA_BSRR (STM32_GPIOA_BASE+STM32_GPI O_BSRR_OFFSET)
# define STM32_GPIOA_BSRR (STM32_GPIOA_BASE+STM32_GPIO_BSRR_OFFSET)
# define STM32_GPIOA_LCKR (STM32_GPIOA_BASE+STM32_GPIO_LCKR_OFFSET)
# define STM32_GPIOA_AFRL (STM32_GPIOA_BASE+STM32_GPIO_AFRL_OFFSET)
# define STM32_GPIOA_AFRH (STM32_GPIOA_BASE+STM32_GPIO_AFRH_OFFSET)
......
......@@ -906,15 +906,12 @@ static int stm32_1wire_isr(int irq, void *context, void *arg)
stm32_1wire_send(priv, READ_TX);
break;
case ONEWIRETASK_WRITEBIT:
*priv->byte = 0;
priv->msgs = NULL;
priv->result = OK;
nxsem_post(&priv->sem_isr);
break;
case ONEWIRETASK_READBIT:
*priv->byte = (dr == READ_RX1) ? 1 : 0;
/* Fall through */
case ONEWIRETASK_WRITEBIT:
priv->msgs = NULL;
priv->result = OK;
nxsem_post(&priv->sem_isr);
......
......@@ -107,13 +107,6 @@ config ARCH_CHIP_TM4C129XNC
select ARCH_CHIP_TM4C
select ARCH_CHIP_TM4C129
select TIVA_HAVE_ETHERNET
config ARCH_CHIP_CC3200
bool "CC3200"
depends on ARCH_CHIP_TIVA
select ARCH_CORTEXM4
select TIVA_HAVE_I2C1
endchoice
# Chip families
......@@ -546,6 +539,22 @@ config TIVA_FLASH
endmenu
config TIVA_RAMVBAR
bool "Set VBAR"
default n
---help---
Set the ARM VBAR register to position interrupt vectors at the
beginning of RAM (vs the beginning of FLASH). The beginning of RAM
is that address defined by CONFIG_RAM_START.
config TIVA_BOARD_CLOCKCONFIG
bool "Board-specific clock configuration"
default n
---help---
If CONFIG_TIVA_BOARD_CLOCKCONFIG is defined, then the board-specific
logic must provide the function tiva_board_clockconfig(). That
function will then be called to perform all clock initialization.
menu "Enable GPIO Interrupts"
config TIVA_GPIO_IRQS
......
/************************************************************************************
* arch/arm/src/tiva/chip/cc3200_memorymap.h
*
* Copyright (C) 2014 Droidifi LLC. All rights reserved.
* Jim Ewing <jim@droidifi.com>
*
* Adapted for the cc3200 from code:
*
* Copyright (C) Gregory Nutt.
* 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 Droidifi 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_TIVA_CHIP_CC3200_MEMORYMAP_H
#define __ARCH_ARM_SRC_TIVA_CHIP_CC3200_MEMORYMAP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Memory map ***********************************************************************/
#if defined(CONFIG_ARCH_CHIP_CC3200)
# define TIVA_FLASH_BASE 0x00000000 /* -0x0007ffff: On-chip FLASH */
/* -0x00ffffff: Reserved */
# define TIVA_ROM_BASE 0x01000000 /* -0x1fffffff: Reserved for ROM */
# define TIVA_SRAM_BASE 0x20000000 /* -0x2003ffff: Bit-banded on-chip SRAM */
/* -0x21ffffff: Reserved */
# define TIVA_ASRAM_BASE 0x22000000 /* -0x23ffffff: Bit-band alias of 20000000- */
/* -0x3fffffff: Reserved */
# define TIVA_PERIPH_BASE 0x40000000 /* -0x4001ffff: FiRM Peripherals */
/* -0x41ffffff: Peripherals */
# define TIVA_APERIPH_BASE 0x42000000 /* -0x43ffffff: Bit-band alias of 40000000- */
# define TIVA_CRYPTO_BASE 0x44030000 /* -0x44039fff: Crypto HW base 44030000- */
/* -0xdfffffff: Reserved */
# define TIVA_ITM_BASE 0xe0000000 /* -0xe0000fff: Instrumentation Trace Macrocell */
# define TIVA_DWT_BASE 0xe0001000 /* -0xe0001fff: Data Watchpoint and Trace */
# define TIVA_FPB_BASE 0xe0002000 /* -0xe0002fff: Flash Patch and Breakpoint */
/* -0xe000dfff: Reserved */
# define TIVA_NVIC_BASE 0xe000e000 /* -0xe000efff: Nested Vectored Interrupt Controller */
/* -0xe003ffff: Reserved */
# define TIVA_TPIU_BASE 0xe0040000 /* -0xe0040fff: Trace Port Interface Unit */
# define TIVA_ETM_BASE 0xe0041000 /* -0xe0041fff: Embedded Trace Macrocell */
/* -0xffffffff: Reserved */
#else
# error "Memory map not specified for this TM4C chip"
#endif
/* Peripheral base addresses ********************************************************/
#if defined(CONFIG_ARCH_CHIP_CC3200)
# define TIVA_WDOG0_BASE (TIVA_PERIPH_BASE + 0x00000) /* -0x00fff: Watchdog Timer 0 */
# define TIVA_GPIOA_BASE (TIVA_PERIPH_BASE + 0x04000) /* -0x04fff: GPIO Port A */
# define TIVA_GPIOB_BASE (TIVA_PERIPH_BASE + 0x05000) /* -0x05fff: GPIO Port B */
# define TIVA_GPIOC_BASE (TIVA_PERIPH_BASE + 0x06000) /* -0x06fff: GPIO Port C */
# define TIVA_GPIOD_BASE (TIVA_PERIPH_BASE + 0x07000) /* -0x07fff: GPIO Port D */
# define TIVA_UART0_BASE (TIVA_PERIPH_BASE + 0x0c000) /* -0x0cfff: UART0 */
# define TIVA_UART1_BASE (TIVA_PERIPH_BASE + 0x0d000) /* -0x0dfff: UART1 */
# define TIVA_I2C0_BASE (TIVA_PERIPH_BASE + 0x20000) /* -0x207ff: I2C0 */
# define TIVA_TIMER0_BASE (TIVA_PERIPH_BASE + 0x30000) /* -0x30fff: 16/32 Timer 0 */
# define TIVA_TIMER1_BASE (TIVA_PERIPH_BASE + 0x31000) /* -0x31fff: 16/32 Timer 1 */
# define TIVA_TIMER2_BASE (TIVA_PERIPH_BASE + 0x32000) /* -0x32fff: 16/32 Timer 2 */
# define TIVA_TIMER3_BASE (TIVA_PERIPH_BASE + 0x33000) /* -0x33fff: 16/32 Timer 3 */
// NOTE: ADC memory location not listed in CC3200 DS
# define TIVA_ADC0_BASE (TIVA_PERIPH_BASE + 0x38000) /* -0x38fff: ADC 0 */
# define TIVA_CONF_REG (TIVA_PERIPH_BASE + 0xf7000) /* -0xf7fff: Configuration registers */
# define TIVA_SYSCON_BASE (TIVA_PERIPH_BASE + 0xfe000) /* -0xfefff: System Control */
# define TIVA_UDMA_BASE (TIVA_PERIPH_BASE + 0xff000) /* -0xfffff: Micro Direct Memory Access */
# define TIVA_ASP_A0 (TIVA_PERIPH_BASE + 0x401c000)/* -0x401efff: McASP A0 */
# define TIVA_SPI_A0 (TIVA_PERIPH_BASE + 0x4020000)/* -0x4020fff: McSPI A0 */
# define TIVA_SPI_A1 (TIVA_PERIPH_BASE + 0x4021000)/* -0x4022fff: McSPI A1 */
# define TIVA_APP_CLK_BASE (TIVA_PERIPH_BASE + 0x4025000)/* -0x4025fff: App Clk */
# define TIVA_APP_CFG_BASE (TIVA_PERIPH_BASE + 0x4026000)/* -0x4026fff: App config */
# define TIVA_OCP_GPRCM_BASE (TIVA_PERIPH_BASE + 0x402d000)/* -0x402dfff: global reset, pwr, clk */
# define TIVA_OCP_SHR_BASE (TIVA_PERIPH_BASE + 0x402e000)/* -0x402efff: OCP shared config */
# define TIVA_HIBERNATE_BASE (TIVA_PERIPH_BASE + 0x402f000)/* -0x402ffff: Hibernation Controller */
/* Crypto Base Addresses */
# define TIVA_TCP_DTHE_BASE (TIVA_CRYPTO_BASE + 0x0000) /* -0x0fff: TCP Checksum & DTHE regs */
# define TIVA_CCM_BASE TIVA_TCP_DTHE_BASE
# define TIVA_SHA_BASE (TIVA_CRYPTO_BASE + 0x5000) /* -0x5fff: MD5/SHA */
# define TIVA_AES_BASE (TIVA_CRYPTO_BASE + 0x7000) /* -0x7fff: AES */
# define TIVA_DES_BASE (TIVA_CRYPTO_BASE + 0x9000) /* -0x9fff: DES */
// NOTE: the following locations are not listed in CC3200 DS
# define TIVA_GPIOAAHB_BASE (TIVA_PERIPH_BASE + 0x58000) /* -0x58fff: GPIO Port A (AHB aperture) */
# define TIVA_GPIOBAHB_BASE (TIVA_PERIPH_BASE + 0x59000) /* -0x59fff: GPIO Port B (AHB aperture) */
# define TIVA_GPIOCAHB_BASE (TIVA_PERIPH_BASE + 0x5a000) /* -0x5afff: GPIO Port C (AHB aperture) */
# define TIVA_GPIODAHB_BASE (TIVA_PERIPH_BASE + 0x5b000) /* -0x5bfff: GPIO Port D (AHB aperture) */
# define TIVA_EPI0_BASE (TIVA_PERIPH_BASE + 0xd0000) /* -0xd0fff: EPI 0 */
# define TIVA_EEPROM_BASE (TIVA_PERIPH_BASE + 0xaf000) /* -0xaffff: EEPROM and Key Locker */
# define TIVA_SYSEXC_BASE (TIVA_PERIPH_BASE + 0xf9000) /* -0xf9fff: System Exception Control */
# define TIVA_FLASHCON_BASE (TIVA_PERIPH_BASE + 0xfd000) /* -0xfdfff: FLASH Control */
#else
# error "Peripheral base addresses not specified for this Stellaris chip"
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
#endif /* __ARCH_ARM_SRC_TIVA_CHIP_CC3200_MEMORYMAP_H */
/************************************************************************************
* arch/arm/src/tiva/chip/cc3200_pinmap.h
*
* Copyright (C) 2014 Droidifi LLC. All rights reserved.
* Author: Jim Ewing <jim@droidifi.com>
*
* Adapted for the cc3200 from code:
*
* Copyright (C) Gregory Nutt.
* 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 Droidifi 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_TIVA_CHIP_CC3200_PINMAP_H
#define __ARCH_ARM_SRC_TIVA_CHIP_CC3200_PINMAP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#if defined(CONFIG_ARCH_CHIP_CC3200)
# define GPIO_ADC_IN0 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_3)
# define GPIO_ADC_IN1 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_2)
# define GPIO_ADC_IN2 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_1)
# define GPIO_ADC_IN3 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_0)
# define GPIO_ADC_IN4 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_3)
# define GPIO_ADC_IN5 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_2)
# define GPIO_ADC_IN6 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_1)
# define GPIO_ADC_IN7 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_0)
# define GPIO_ADC_IN8 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_5)
# define GPIO_ADC_IN9 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_4)
# define GPIO_ADC_IN10 (GPIO_FUNC_ANINPUT | GPIO_PORTB | GPIO_PIN_4)
# define GPIO_ADC_IN11 (GPIO_FUNC_ANINPUT | GPIO_PORTB | GPIO_PIN_5)
# define GPIO_CORE_TRCLK (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PADTYPE_ODWPU | GPIO_PORTF | GPIO_PIN_3)
# define GPIO_CORE_TRD0 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PADTYPE_ODWPU | GPIO_PORTF | GPIO_PIN_2)
# define GPIO_CORE_TRD1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PADTYPE_ODWPU | GPIO_PORTF | GPIO_PIN_1)
# define GPIO_I2C0_SCL (GPIO_FUNC_PFOUTPUT | GPIO_ALT_3 | GPIO_PORTB | GPIO_PIN_2)
# define GPIO_I2C0_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTB | GPIO_PIN_3)
# define GPIO_I2C1_SCL (GPIO_FUNC_PFOUTPUT | GPIO_ALT_3 | GPIO_PORTA | GPIO_PIN_6)
# define GPIO_I2C1_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTA | GPIO_PIN_7)
# define GPIO_I2C2_SCL (GPIO_FUNC_PFOUTPUT | GPIO_ALT_3 | GPIO_PORTE | GPIO_PIN_4)
# define GPIO_I2C2_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTE | GPIO_PIN_5)
# define GPIO_I2C3_SCL (GPIO_FUNC_PFOUTPUT | GPIO_ALT_3 | GPIO_PORTD | GPIO_PIN_0)
# define GPIO_I2C3_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTD | GPIO_PIN_1)
# define GPIO_JTAG_SWCLK (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_0)
# define GPIO_JTAG_SWDIO (GPIO_FUNC_PFIO | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_1)
# define GPIO_JTAG_SWO (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_3)
# define GPIO_JTAG_TCK (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_0)
# define GPIO_JTAG_TDI (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_2)
# define GPIO_JTAG_TDO (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_3)
# define GPIO_JTAG_TMS (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_1)
# define GPIO_SYSCON_NMI_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTD | GPIO_PIN_7)
# define GPIO_SYSCON_NMI_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTF | GPIO_PIN_0)
# define GPIO_TIM0_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_6)
# define GPIO_TIM0_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_0)
# define GPIO_TIM0_CCP1_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_7)
# define GPIO_TIM0_CCP1_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_1)
# define GPIO_TIM1_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_4)
# define GPIO_TIM1_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_2)
# define GPIO_TIM1_CCP1_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_5)
# define GPIO_TIM1_CCP1_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_3)
# define GPIO_TIM2_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_0)
# define GPIO_TIM2_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_4)
# define GPIO_TIM2_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_1)
# define GPIO_TIM3_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_2)
# define GPIO_TIM4_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_1)
# define GPIO_UART0_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_0)
# define GPIO_UART0_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_1)
# define GPIO_UART1_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_0)
# define GPIO_UART1_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_1)
# define GPIO_UART1_CTS_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_1)
# define GPIO_UART1_CTS_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_5)
# define GPIO_UART1_RTS_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_0)
# define GPIO_UART1_RTS_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_4)
# define GPIO_UART1_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_0)
# define GPIO_UART1_RX_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTC | GPIO_PIN_4)
# define GPIO_UART1_TX_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_1)
# define GPIO_UART1_TX_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTC | GPIO_PIN_5)
#else
# error "Unknown TIVA chip"
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#endif /* __ARCH_ARM_SRC_TIVA_CHIP_CC3200_PINMAP_H */
This diff is collapsed.
/************************************************************************************
* arch/arm/src/tiva/chip/cc3200_vectors.h
*
* Copyright (C) 2014 Droidifi LLC. All rights reserved.
* Author: Jim Ewing <jim@droidifi.com>
*
* Adapted for the cc3200 from code:
*
* Copyright (C) Gregory Nutt.
* 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 Droidifi 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.
*
************************************************************************************/
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Vectors
************************************************************************************/
/* This file is included by tiva_vectors.S. It provides the macro VECTOR that
* supplies each Tiva vector in terms of a (lower-case) ISR label and an
* (upper-case) IRQ number as defined in arch/arm/include/tiva/tm4c_irq.h.
* tiva_vectors.S will define the VECTOR in different ways in order to generate
* the interrupt vectors and handlers in their final form.
*/
#if defined(CONFIG_ARCH_CHIP_CC3200)
/* If the common ARMv7-M vector handling is used, then all it needs is the following
* definition that provides the number of supported vectors.
*/
# ifdef CONFIG_ARMV7M_CMNVECTOR
/* Reserve 155 interrupt table entries for I/O interrupts. */
ARMV7M_PERIPHERAL_INTERRUPTS 155
# else
VECTOR(tiva_gpioa, TIVA_IRQ_GPIOA) /* Vector 16: GPIO Port A */
VECTOR(tiva_gpiob, TIVA_IRQ_GPIOB) /* Vector 17: GPIO Port B */
VECTOR(tiva_gpioc, TIVA_IRQ_GPIOC) /* Vector 18: GPIO Port C */
VECTOR(tiva_gpiod, TIVA_IRQ_GPIOD) /* Vector 19: GPIO Port D */
UNUSED(TIVA_RESERVED_20) /* Vector 20: Reserved */
VECTOR(tiva_uart0, TIVA_IRQ_UART0) /* Vector 21: UART 0 */
VECTOR(tiva_uart1, TIVA_IRQ_UART1) /* Vector 22: UART 1 */
UNUSED(TIVA_RESERVED_23) /* Vector 23: Reserved */
VECTOR(tiva_i2c0, TIVA_IRQ_I2C0) /* Vector 24: I2C 0 */
UNUSED(TIVA_RESERVED_25) /* Vector 25: Reserved */
UNUSED(TIVA_RESERVED_26) /* Vector 26: Reserved */
UNUSED(TIVA_RESERVED_27) /* Vector 27: Reserved */
UNUSED(TIVA_RESERVED_28) /* Vector 28: Reserved */
UNUSED(TIVA_RESERVED_29) /* Vector 29: Reserved */
VECTOR(tiva_adc0, TIVA_IRQ_ADC0) /* Vector 30: ADC Sequence 0 */
VECTOR(tiva_adc1, TIVA_IRQ_ADC1) /* Vector 31: ADC Sequence 1 */
VECTOR(tiva_adc2, TIVA_IRQ_ADC2) /* Vector 32: ADC Sequence 2 */
VECTOR(tiva_adc3, TIVA_IRQ_ADC3) /* Vector 33: ADC Sequence 3 */
VECTOR(tiva_wdog, TIVA_IRQ_WDOG) /* Vector 34: Watchdog Timers 0 and 1 */
VECTOR(tiva_timer0a, TIVA_IRQ_TIMER0A) /* Vector 35: 16/32-Bit Timer 0 A */
VECTOR(tiva_timer0b, TIVA_IRQ_TIMER0B) /* Vector 36: 16/32-Bit Timer 0 B */
VECTOR(tiva_timer1a, TIVA_IRQ_TIMER1A) /* Vector 37: 16/32-Bit Timer 1 A */
VECTOR(tiva_timer1b, TIVA_IRQ_TIMER1B) /* Vector 38: 16/32-Bit Timer 1 B */
VECTOR(tiva_timer2a, TIVA_IRQ_TIMER2A) /* Vector 39: 16/32-Bit Timer 2 A */
VECTOR(tiva_timer2b, TIVA_IRQ_TIMER2B) /* Vector 40: 16/32-Bit Timer 2 B */
UNUSED(TIVA_RESERVED_41) /* Vector 41: Reserved */
UNUSED(TIVA_RESERVED_42) /* Vector 42: Reserved */
UNUSED(TIVA_RESERVED_43) /* Vector 43: Reserved */
VECTOR(tiva_syscon, TIVA_IRQ_SYSCON) /* Vector 44: System Control */
VECTOR(tiva_flashcon, TIVA_IRQ_FLASHCON) /* Vector 45: FLASH and EEPROM Control */
UNUSED(TIVA_RESERVED_46) /* Vector 46: Reserved */
UNUSED(TIVA_RESERVED_47) /* Vector 47: Reserved */
UNUSED(TIVA_RESERVED_48) /* Vector 48: Reserved */
UNUSED(TIVA_RESERVED_49) /* Vector 49: Reserved */
UNUSED(TIVA_RESERVED_50) /* Vector 50: Reserved */
VECTOR(tiva_timer3a, TIVA_IRQ_TIMER3A) /* Vector 51: 16/32-Bit Timer 3 A */
VECTOR(tiva_timer3b, TIVA_IRQ_TIMER3B) /* Vector 52: 16/32-Bit Timer 3 B */
UNUSED(TIVA_RESERVED_53) /* Vector 53: Reserved */
UNUSED(TIVA_RESERVED_54) /* Vector 54: Reserved */
UNUSED(TIVA_RESERVED_55) /* Vector 55: Reserved */
UNUSED(TIVA_RESERVED_56) /* Vector 56: Reserved */
UNUSED(TIVA_RESERVED_57) /* Vector 57: Reserved */
UNUSED(TIVA_RESERVED_58) /* Vector 58: Reserved */
VECTOR(tiva_hibernate, TIVA_IRQ_HIBERNATE) /* Vector 59: Hibernation Module */
UNUSED(TIVA_RESERVED_60) /* Vector 60: Reserved */
UNUSED(TIVA_RESERVED_61) /* Vector 61: Reserved */
VECTOR(tiva_udmasoft, TIVA_IRQ_UDMASOFT) /* Vector 62: uDMA Software */
VECTOR(tiva_udmaerro, TIVA_IRQ_UDMAERROR)/* Vector 63: uDMA Error */
UNUSED(TIVA_RESERVED_64) /* Vector 64: Reserved */
UNUSED(TIVA_RESERVED_65) /* Vector 65: Reserved */
UNUSED(TIVA_RESERVED_66) /* Vector 66: Reserved */
UNUSED(TIVA_RESERVED_67) /* Vector 67: Reserved */
VECTOR(tiva_i2s0, TIVA_IRQ_I2S0) /* Vector 68: I2S 0 */
VECTOR(tiva_epi, TIVA_IRQ_EPI) /* Vector 69: EPI */
UNUSED(TIVA_RESERVED_70) /* Vector 70: Reserved */
UNUSED(TIVA_RESERVED_71) /* Vector 71: Reserved */
UNUSED(TIVA_RESERVED_72) /* Vector 72: Reserved */
UNUSED(TIVA_RESERVED_73) /* Vector 73: Reserved */
UNUSED(TIVA_RESERVED_74) /* Vector 74: Reserved */
UNUSED(TIVA_RESERVED_75) /* Vector 75: Reserved */
UNUSED(TIVA_RESERVED_76) /* Vector 76: Reserved */
UNUSED(TIVA_RESERVED_77) /* Vector 77: Reserved */
UNUSED(TIVA_RESERVED_78) /* Vector 78: Reserved */
UNUSED(TIVA_RESERVED_79) /* Vector 79: Reserved */
UNUSED(TIVA_RESERVED_80) /* Vector 80: Reserved */
UNUSED(TIVA_RESERVED_81) /* Vector 81: Reserved */
UNUSED(TIVA_RESERVED_82) /* Vector 82: Reserved */
UNUSED(TIVA_RESERVED_83) /* Vector 83: Reserved */
UNUSED(TIVA_RESERVED_84) /* Vector 84: Reserved */
UNUSED(TIVA_RESERVED_85) /* Vector 85: Reserved */
UNUSED(TIVA_RESERVED_86) /* Vector 86: Reserved */
UNUSED(TIVA_RESERVED_87) /* Vector 87: Reserved */
UNUSED(TIVA_RESERVED_88) /* Vector 88: Reserved */
UNUSED(TIVA_RESERVED_89) /* Vector 89: Reserved */
UNUSED(TIVA_RESERVED_90) /* Vector 90: Reserved */
UNUSED(TIVA_RESERVED_91) /* Vector 91: Reserved */
UNUSED(TIVA_RESERVED_92) /* Vector 92: Reserved */
UNUSED(TIVA_RESERVED_93) /* Vector 93: Reserved */
UNUSED(TIVA_RESERVED_94) /* Vector 94: Reserved */
UNUSED(TIVA_RESERVED_95) /* Vector 95: Reserved */
UNUSED(TIVA_RESERVED_96) /* Vector 96: Reserved */
UNUSED(TIVA_RESERVED_97) /* Vector 97: Reserved */
UNUSED(TIVA_RESERVED_98) /* Vector 98: Reserved */
UNUSED(TIVA_RESERVED_99) /* Vector 99: Reserved */
UNUSED(TIVA_RESERVED_100) /* Vector 100: Reserved */
UNUSED(TIVA_RESERVED_101) /* Vector 101: Reserved */
UNUSED(TIVA_RESERVED_102) /* Vector 102: Reserved */
UNUSED(TIVA_RESERVED_103) /* Vector 103: Reserved */
UNUSED(TIVA_RESERVED_104) /* Vector 104: Reserved */
UNUSED(TIVA_RESERVED_105) /* Vector 105: Reserved */
UNUSED(TIVA_RESERVED_106) /* Vector 106: Reserved */
UNUSED(TIVA_RESERVED_107) /* Vector 107: Reserved */
UNUSED(TIVA_RESERVED_108) /* Vector 108: Reserved */
UNUSED(TIVA_RESERVED_109) /* Vector 109: Reserved */
UNUSED(TIVA_RESERVED_110) /* Vector 110: Reserved */
UNUSED(TIVA_RESERVED_111) /* Vector 111: Reserved */
UNUSED(TIVA_RESERVED_112) /* Vector 112: Reserved */
UNUSED(TIVA_RESERVED_113) /* Vector 113: Reserved */
UNUSED(TIVA_RESERVED_114) /* Vector 114: Reserved */
UNUSED(TIVA_RESERVED_115) /* Vector 115: Reserved */
UNUSED(TIVA_RESERVED_116) /* Vector 116: Reserved */
UNUSED(TIVA_RESERVED_117) /* Vector 117: Reserved */
UNUSED(TIVA_RESERVED_118) /* Vector 118: Reserved */
UNUSED(TIVA_RESERVED_119) /* Vector 119: Reserved */
UNUSED(TIVA_RESERVED_120) /* Vector 120: Reserved */
UNUSED(TIVA_RESERVED_121) /* Vector 121: Reserved */
VECTOR(tiva_system, TIVA_IRQ_SYSTEM) /* Vector 122: System Exception (imprecise) */
UNUSED(TIVA_RESERVED_123) /* Vector 123: Reserved */
UNUSED(TIVA_RESERVED_124) /* Vector 124: Reserved */
UNUSED(TIVA_RESERVED_125) /* Vector 125: Reserved */
UNUSED(TIVA_RESERVED_126) /* Vector 126: Reserved */
UNUSED(TIVA_RESERVED_127) /* Vector 127: Reserved */
UNUSED(TIVA_RESERVED_128) /* Vector 128: Reserved */
UNUSED(TIVA_RESERVED_129) /* Vector 129: Reserved */
UNUSED(TIVA_RESERVED_130) /* Vector 130: Reserved */
UNUSED(TIVA_RESERVED_131) /* Vector 131: Reserved */
UNUSED(TIVA_RESERVED_132) /* Vector 132: Reserved */
UNUSED(TIVA_RESERVED_133) /* Vector 133: Reserved */
UNUSED(TIVA_RESERVED_134) /* Vector 134: Reserved */
UNUSED(TIVA_RESERVED_135) /* Vector 135: Reserved */
UNUSED(TIVA_RESERVED_136) /* Vector 136: Reserved */
UNUSED(TIVA_RESERVED_137) /* Vector 137: Reserved */
UNUSED(TIVA_RESERVED_138) /* Vector 138: Reserved */
UNUSED(TIVA_RESERVED_139) /* Vector 139: Reserved */
UNUSED(TIVA_RESERVED_140) /* Vector 140: Reserved */
UNUSED(TIVA_RESERVED_141) /* Vector 141: Reserved */
UNUSED(TIVA_RESERVED_142) /* Vector 142: Reserved */
UNUSED(TIVA_RESERVED_143) /* Vector 143: Reserved */
UNUSED(TIVA_RESERVED_144) /* Vector 144: Reserved */
UNUSED(TIVA_RESERVED_145) /* Vector 145: Reserved */
UNUSED(TIVA_RESERVED_146) /* Vector 146: Reserved */
UNUSED(TIVA_RESERVED_147) /* Vector 147: Reserved */
UNUSED(TIVA_RESERVED_148) /* Vector 148: Reserved */
UNUSED(TIVA_RESERVED_149) /* Vector 149: Reserved */
UNUSED(TIVA_RESERVED_150) /* Vector 150: Reserved */
UNUSED(TIVA_RESERVED_151) /* Vector 151: Reserved */
UNUSED(TIVA_RESERVED_152) /* Vector 152: Reserved */
UNUSED(TIVA_RESERVED_153) /* Vector 153: Reserved */
UNUSED(TIVA_RESERVED_154) /* Vector 154: Reserved */
UNUSED(TIVA_RESERVED_155) /* Vector 155: Reserved */
UNUSED(TIVA_RESERVED_156) /* Vector 156: Reserved */
UNUSED(TIVA_RESERVED_157) /* Vector 157: Reserved */
UNUSED(TIVA_RESERVED_158) /* Vector 158: Reserved */
UNUSED(TIVA_RESERVED_159) /* Vector 159: Reserved */
UNUSED(TIVA_RESERVED_160) /* Vector 160: Reserved */
UNUSED(TIVA_RESERVED_161) /* Vector 161: Reserved */
UNUSED(TIVA_RESERVED_162) /* Vector 162: Reserved */
UNUSED(TIVA_RESERVED_163) /* Vector 163: Reserved */
UNUSED(TIVA_RESERVED_164) /* Vector 164: SHA HW */
UNUSED(TIVA_RESERVED_165) /* Vector 165: Reserved */
UNUSED(TIVA_RESERVED_166) /* Vector 166: Reserved */
UNUSED(TIVA_RESERVED_167) /* Vector 167: AES HW */
UNUSED(TIVA_RESERVED_168) /* Vector 168: Reserved */
UNUSED(TIVA_RESERVED_169) /* Vector 169: DES HW */
UNUSED(TIVA_RESERVED_170) /* Vector 170: Reserved */
UNUSED(TIVA_RESERVED_171) /* Vector 171: Reserved */
UNUSED(TIVA_RESERVED_172) /* Vector 172: Reserved */
UNUSED(TIVA_RESERVED_173) /* Vector 173: Reserved */
UNUSED(TIVA_RESERVED_174) /* Vector 174: Reserved */
UNUSED(TIVA_RESERVED_175) /* Vector 175: SDIO */
UNUSED(TIVA_RESERVED_176) /* Vector 176: Reserved */
UNUSED(TIVA_RESERVED_177) /* Vector 177: McASP 0 */
UNUSED(TIVA_RESERVED_178) /* Vector 178: Reserved */
UNUSED(TIVA_RESERVED_179) /* Vector 179: Camera A0 */
UNUSED(TIVA_RESERVED_180) /* Vector 180: Reserved */
UNUSED(TIVA_RESERVED_181) /* Vector 181: Reserved */
UNUSED(TIVA_RESERVED_182) /* Vector 182: Reserved */
UNUSED(TIVA_RESERVED_183) /* Vector 183: Reserved */
UNUSED(TIVA_RESERVED_184) /* Vector 184: RAM Err */
UNUSED(TIVA_RESERVED_185) /* Vector 185: Reserved */
UNUSED(TIVA_RESERVED_186) /* Vector 186: Reserved */
UNUSED(TIVA_RESERVED_187) /* Vector 187: NWP IC interocessor comm */
UNUSED(TIVA_RESERVED_188) /* Vector 188: Pwr, Rst, Clk */
UNUSED(TIVA_RESERVED_189) /* Vector 189: From Top Die */
UNUSED(TIVA_RESERVED_190) /* Vector 190: Reserved */
UNUSED(TIVA_RESERVED_191) /* Vector 191: SPI S0 */
UNUSED(TIVA_RESERVED_192) /* Vector 192: SPI A0 */
UNUSED(TIVA_RESERVED_193) /* Vector 193: SPI A1 */
UNUSED(TIVA_RESERVED_194) /* Vector 194: Reserved */
# endif /* CONFIG_ARMV7M_CMNVECTOR */
#else
# error "Vectors not known for this Tiva chip"
#endif /* defined(CONFIG_ARCH_CHIP_CC3200) */
......@@ -50,8 +50,7 @@
#if defined(CONFIG_ARCH_CHIP_LM3S6965) || defined(CONFIG_ARCH_CHIP_LM4F120) || \
defined(CONFIG_ARCH_CHIP_LM3S8962) || defined(CONFIG_ARCH_CHIP_LM3S9B96) || \
defined(CONFIG_ARCH_CHIP_TM4C123GH6ZRB) || defined(CONFIG_ARCH_CHIP_TM4C123GH6PMI) || \
defined(CONFIG_ARCH_CHIP_CC3200)
defined(CONFIG_ARCH_CHIP_TM4C123GH6ZRB) || defined(CONFIG_ARCH_CHIP_TM4C123GH6PMI)
/* These parts all support a 1KiB erase page size and a total FLASH memory size
* of 256Kib or 256 pages.
......
......@@ -50,8 +50,6 @@
# include "chip/lm4f_memorymap.h"
#elif defined(CONFIG_ARCH_CHIP_TM4C)
# include "chip/tm4c_memorymap.h"
#elif defined(CONFIG_ARCH_CHIP_CC3200)
# include "chip/cc3200_memorymap.h"
#else
# error "Unsupported Tiva/Stellaris memory map"
#endif
......
......@@ -50,8 +50,6 @@
# include "chip/lm4f_pinmap.h"
#elif defined(CONFIG_ARCH_CHIP_TM4C)
# include "chip/tm4c_pinmap.h"
#elif defined(CONFIG_ARCH_CHIP_CC3200)
# include "chip/cc3200_pinmap.h"
#else
# error "Unsupported Tiva/Stellaris PIN mapping"
#endif
......