CC2538: Use CMSIS-CORE
Switch to CMSIS-CORE and remove the duplicate code. Signed-off-by: Benoît Thébaudeau <benoit.thebaudeau.dev@gmail.com>
This commit is contained in:
parent
9195b49c18
commit
ab1491be69
|
@ -42,7 +42,7 @@ endif
|
||||||
CLEAN += symbols.c symbols.h *.d *.elf *.hex
|
CLEAN += symbols.c symbols.h *.d *.elf *.hex
|
||||||
|
|
||||||
### CPU-dependent directories
|
### CPU-dependent directories
|
||||||
CONTIKI_CPU_DIRS = . dev usb
|
CONTIKI_CPU_DIRS = ../arm/common/CMSIS . dev usb
|
||||||
|
|
||||||
### Use the existing debug I/O in cpu/arm/common
|
### Use the existing debug I/O in cpu/arm/common
|
||||||
CONTIKI_CPU_DIRS += ../arm/common/dbg-io
|
CONTIKI_CPU_DIRS += ../arm/common/dbg-io
|
||||||
|
@ -52,7 +52,7 @@ CONTIKI_CPU_DIRS += ../cc253x/usb/common ../cc253x/usb/common/cdc-acm
|
||||||
|
|
||||||
### CPU-dependent source files
|
### CPU-dependent source files
|
||||||
CONTIKI_CPU_SOURCEFILES += soc.c clock.c rtimer-arch.c uart.c watchdog.c
|
CONTIKI_CPU_SOURCEFILES += soc.c clock.c rtimer-arch.c uart.c watchdog.c
|
||||||
CONTIKI_CPU_SOURCEFILES += nvic.c cpu.c sys-ctrl.c gpio.c ioc.c spi.c adc.c
|
CONTIKI_CPU_SOURCEFILES += nvic.c sys-ctrl.c gpio.c ioc.c spi.c adc.c
|
||||||
CONTIKI_CPU_SOURCEFILES += crypto.c aes.c ecb.c cbc.c ctr.c cbc-mac.c gcm.c
|
CONTIKI_CPU_SOURCEFILES += crypto.c aes.c ecb.c cbc.c ctr.c cbc-mac.c gcm.c
|
||||||
CONTIKI_CPU_SOURCEFILES += ccm.c sha256.c
|
CONTIKI_CPU_SOURCEFILES += ccm.c sha256.c
|
||||||
CONTIKI_CPU_SOURCEFILES += cc2538-aes-128.c cc2538-ccm-star.c
|
CONTIKI_CPU_SOURCEFILES += cc2538-aes-128.c cc2538-ccm-star.c
|
||||||
|
@ -123,4 +123,4 @@ LDGENFLAGS += -x c -P -E
|
||||||
# NB: Assumes LDSCRIPT was not overridden and is in $(OBJECTDIR)
|
# NB: Assumes LDSCRIPT was not overridden and is in $(OBJECTDIR)
|
||||||
$(LDSCRIPT): $(SOURCE_LDSCRIPT) FORCE | $(OBJECTDIR)
|
$(LDSCRIPT): $(SOURCE_LDSCRIPT) FORCE | $(OBJECTDIR)
|
||||||
$(TRACE_CC)
|
$(TRACE_CC)
|
||||||
$(Q)$(CC) $(LDGENFLAGS) $< -o $@
|
$(Q)$(CC) $(LDGENFLAGS) $< | grep -v '^\s*#\s*pragma\>' > $@
|
||||||
|
|
144
cpu/cc2538/cc2538_cm3.h
Normal file
144
cpu/cc2538/cc2538_cm3.h
Normal file
|
@ -0,0 +1,144 @@
|
||||||
|
/*
|
||||||
|
* Template:
|
||||||
|
* Copyright (c) 2012 ARM LIMITED
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* CC2538:
|
||||||
|
* Copyright (c) 2016, Benoît Thébaudeau <benoit.thebaudeau.dev@gmail.com>
|
||||||
|
* 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 of the copyright holder 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 HOLDER 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.
|
||||||
|
*/
|
||||||
|
/**
|
||||||
|
* \addtogroup cc2538
|
||||||
|
* @{
|
||||||
|
*
|
||||||
|
* \defgroup cc2538-cm3 CC2538 Cortex-M3
|
||||||
|
*
|
||||||
|
* CC2538 Cortex-M3 CMSIS definitions
|
||||||
|
* @{
|
||||||
|
*
|
||||||
|
* \file
|
||||||
|
* CMSIS Cortex-M3 core peripheral access layer header file for CC2538
|
||||||
|
*/
|
||||||
|
#ifndef CC2538_CM3_H
|
||||||
|
#define CC2538_CM3_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** \defgroup CC2538_CMSIS CC2538 CMSIS Definitions
|
||||||
|
* Configuration of the Cortex-M3 Processor and Core Peripherals
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** \name Interrupt Number Definition
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef enum IRQn
|
||||||
|
{
|
||||||
|
/****** Cortex-M3 Processor Exceptions Numbers ****************************/
|
||||||
|
NonMaskableInt_IRQn = -14, /**< 2 Non Maskable Interrupt */
|
||||||
|
HardFault_IRQn = -13, /**< 3 HardFault Interrupt */
|
||||||
|
MemoryManagement_IRQn = -12, /**< 4 Memory Management Interrupt */
|
||||||
|
BusFault_IRQn = -11, /**< 5 Bus Fault Interrupt */
|
||||||
|
UsageFault_IRQn = -10, /**< 6 Usage Fault Interrupt */
|
||||||
|
SVCall_IRQn = -5, /**< 11 SV Call Interrupt */
|
||||||
|
DebugMonitor_IRQn = -4, /**< 12 Debug Monitor Interrupt */
|
||||||
|
PendSV_IRQn = -2, /**< 14 Pend SV Interrupt */
|
||||||
|
SysTick_IRQn = -1, /**< 15 System Tick Interrupt */
|
||||||
|
|
||||||
|
/****** CC2538-Specific Interrupt Numbers *********************************/
|
||||||
|
GPIO_A_IRQn = 0, /**< GPIO port A Interrupt */
|
||||||
|
GPIO_B_IRQn = 1, /**< GPIO port B Interrupt */
|
||||||
|
GPIO_C_IRQn = 2, /**< GPIO port C Interrupt */
|
||||||
|
GPIO_D_IRQn = 3, /**< GPIO port D Interrupt */
|
||||||
|
UART0_IRQn = 5, /**< UART0 Interrupt */
|
||||||
|
UART1_IRQn = 6, /**< UART1 Interrupt */
|
||||||
|
SSI0_IRQn = 7, /**< SSI0 Interrupt */
|
||||||
|
I2C_IRQn = 8, /**< I²C Interrupt */
|
||||||
|
ADC_IRQn = 14, /**< ADC Interrupt */
|
||||||
|
WDT_IRQn = 18, /**< Watchdog Timer Interrupt */
|
||||||
|
GPT0A_IRQn = 19, /**< GPTimer 0A Interrupt */
|
||||||
|
GPT0B_IRQn = 20, /**< GPTimer 0B Interrupt */
|
||||||
|
GPT1A_IRQn = 21, /**< GPTimer 1A Interrupt */
|
||||||
|
GPT1B_IRQn = 22, /**< GPTimer 1B Interrupt */
|
||||||
|
GPT2A_IRQn = 23, /**< GPTimer 2A Interrupt */
|
||||||
|
GPT2B_IRQn = 24, /**< GPTimer 2B Interrupt */
|
||||||
|
ADC_CMP_IRQn = 25, /**< Analog Comparator Interrupt */
|
||||||
|
RF_TX_RX_ALT_IRQn = 26, /**< RF Tx/Rx (Alternate) Interrupt */
|
||||||
|
RF_ERR_ALT_IRQn = 27, /**< RF Error (Alternate) Interrupt */
|
||||||
|
SYS_CTRL_IRQn = 28, /**< System Control Interrupt */
|
||||||
|
FLASH_CTRL_IRQn = 29, /**< Flash memory Control Interrupt */
|
||||||
|
AES_ALT_IRQn = 30, /**< AES (Alternate) Interrupt */
|
||||||
|
PKA_ALT_IRQn = 31, /**< PKA (Alternate) Interrupt */
|
||||||
|
SMT_ALT_IRQn = 32, /**< SM Timer (Alternate) Interrupt */
|
||||||
|
MACT_ALT_IRQn = 33, /**< MAC Timer (Alternate) Interrupt */
|
||||||
|
SSI1_IRQn = 34, /**< SSI1 Interrupt */
|
||||||
|
GPT3A_IRQn = 35, /**< GPTimer 3A Interrupt */
|
||||||
|
GPT3B_IRQn = 36, /**< GPTimer 3B Interrupt */
|
||||||
|
UDMA_SW_IRQn = 46, /**< µDMA Software Interrupt */
|
||||||
|
UDMA_ERR_IRQn = 47, /**< µDMA Error Interrupt */
|
||||||
|
USB_IRQn = 140, /**< USB Interrupt */
|
||||||
|
RF_TX_RX_IRQn = 141, /**< RF Tx/Rx Interrupt */
|
||||||
|
RF_ERR_IRQn = 142, /**< RF Error Interrupt */
|
||||||
|
AES_IRQn = 143, /**< AES Interrupt */
|
||||||
|
PKA_IRQn = 144, /**< PKA Interrupt */
|
||||||
|
SMT_IRQn = 145, /**< SM Timer Interrupt */
|
||||||
|
MACT_IRQn = 146 /**< MAC Timer Interrupt */
|
||||||
|
} IRQn_Type;
|
||||||
|
|
||||||
|
/** @} */
|
||||||
|
|
||||||
|
/** \name Processor and Core Peripheral Section
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Configuration of the Cortex-M3 Processor and Core Peripherals */
|
||||||
|
#define __CM3_REV 0x0200 /**< Core Revision r2p0 */
|
||||||
|
#define __MPU_PRESENT 1 /**< MPU present or not */
|
||||||
|
#define __NVIC_PRIO_BITS 3 /**< Number of Bits used for Priority Levels */
|
||||||
|
#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */
|
||||||
|
|
||||||
|
/** @} */
|
||||||
|
|
||||||
|
/** @} */ /* CC2538_CMSIS */
|
||||||
|
|
||||||
|
#include <core_cm3.h> /* Cortex-M3 processor and core peripherals */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* CC2538_CM3_H */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
* @}
|
||||||
|
*/
|
|
@ -49,7 +49,7 @@
|
||||||
* Clock driver implementation for the TI cc2538
|
* Clock driver implementation for the TI cc2538
|
||||||
*/
|
*/
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "systick.h"
|
#include "cc2538_cm3.h"
|
||||||
#include "reg.h"
|
#include "reg.h"
|
||||||
#include "cpu.h"
|
#include "cpu.h"
|
||||||
#include "dev/gptimer.h"
|
#include "dev/gptimer.h"
|
||||||
|
@ -69,12 +69,12 @@
|
||||||
#endif
|
#endif
|
||||||
#define PRESCALER_VALUE (SYS_CTRL_SYS_CLOCK / SYS_CTRL_1MHZ - 1)
|
#define PRESCALER_VALUE (SYS_CTRL_SYS_CLOCK / SYS_CTRL_1MHZ - 1)
|
||||||
|
|
||||||
/* Reload value for SysTick counter */
|
/* Period of the SysTick counter expressed as a number of ticks */
|
||||||
#if SYS_CTRL_SYS_CLOCK % CLOCK_SECOND
|
#if SYS_CTRL_SYS_CLOCK % CLOCK_SECOND
|
||||||
/* Too low clock speeds will lead to reduced accurracy */
|
/* Too low clock speeds will lead to reduced accurracy */
|
||||||
#error System clock speed too slow for CLOCK_SECOND, accuracy reduced
|
#error System clock speed too slow for CLOCK_SECOND, accuracy reduced
|
||||||
#endif
|
#endif
|
||||||
#define RELOAD_VALUE (SYS_CTRL_SYS_CLOCK / CLOCK_SECOND - 1)
|
#define SYSTICK_PERIOD (SYS_CTRL_SYS_CLOCK / CLOCK_SECOND)
|
||||||
|
|
||||||
static volatile uint64_t rt_ticks_startup = 0, rt_ticks_epoch = 0;
|
static volatile uint64_t rt_ticks_startup = 0, rt_ticks_epoch = 0;
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
@ -92,13 +92,7 @@ static volatile uint64_t rt_ticks_startup = 0, rt_ticks_epoch = 0;
|
||||||
void
|
void
|
||||||
clock_init(void)
|
clock_init(void)
|
||||||
{
|
{
|
||||||
REG(SYSTICK_STRELOAD) = RELOAD_VALUE;
|
SysTick_Config(SYSTICK_PERIOD);
|
||||||
|
|
||||||
/* System clock source, Enable */
|
|
||||||
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_CLK_SRC | SYSTICK_STCTRL_ENABLE;
|
|
||||||
|
|
||||||
/* Enable the SysTick Interrupt */
|
|
||||||
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_INTEN;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Remove the clock gate to enable GPT0 and then initialise it
|
* Remove the clock gate to enable GPT0 and then initialise it
|
||||||
|
@ -230,12 +224,12 @@ void
|
||||||
clock_adjust(void)
|
clock_adjust(void)
|
||||||
{
|
{
|
||||||
/* Halt the SysTick while adjusting */
|
/* Halt the SysTick while adjusting */
|
||||||
REG(SYSTICK_STCTRL) &= ~SYSTICK_STCTRL_ENABLE;
|
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
|
||||||
|
|
||||||
update_ticks();
|
update_ticks();
|
||||||
|
|
||||||
/* Re-Start the SysTick */
|
/* Re-Start the SysTick */
|
||||||
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_ENABLE;
|
SysTick->CTRL |= SysTick_CTRL_ENABLE_Msk;
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -1,72 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2012, Texas Instruments Incorporated - http://www.ti.com/
|
|
||||||
* 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 of the copyright holder 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 HOLDER 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.
|
|
||||||
*/
|
|
||||||
/**
|
|
||||||
* \addtogroup cc2538-cpu
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* \file
|
|
||||||
* Implementations of interrupt control on the cc2538 Cortex-M3 micro
|
|
||||||
*/
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
unsigned long __attribute__((naked))
|
|
||||||
cpu_cpsie(void)
|
|
||||||
{
|
|
||||||
unsigned long ret;
|
|
||||||
|
|
||||||
/* Read PRIMASK and enable interrupts */
|
|
||||||
__asm(" mrs r0, PRIMASK\n"
|
|
||||||
" cpsie i\n"
|
|
||||||
" bx lr\n"
|
|
||||||
: "=r" (ret));
|
|
||||||
|
|
||||||
/* The inline asm returns, we never reach here.
|
|
||||||
* We add a return statement to keep the compiler happy */
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
unsigned long __attribute__((naked))
|
|
||||||
cpu_cpsid(void)
|
|
||||||
{
|
|
||||||
unsigned long ret;
|
|
||||||
|
|
||||||
/* Read PRIMASK and disable interrupts */
|
|
||||||
__asm(" mrs r0, PRIMASK\n"
|
|
||||||
" cpsid i\n"
|
|
||||||
" bx lr\n"
|
|
||||||
: "=r" (ret));
|
|
||||||
|
|
||||||
/* The inline asm returns, we never reach here.
|
|
||||||
* We add a return statement to keep the compiler happy */
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
|
|
||||||
/** @} */
|
|
|
@ -54,17 +54,13 @@
|
||||||
#ifndef CPU_H_
|
#ifndef CPU_H_
|
||||||
#define CPU_H_
|
#define CPU_H_
|
||||||
|
|
||||||
/** \brief Disables all CPU interrupts */
|
#include "cc2538_cm3.h"
|
||||||
unsigned long cpu_cpsid(void);
|
|
||||||
|
|
||||||
/** \brief Enables all CPU interrupts */
|
/** \brief Enables all CPU interrupts */
|
||||||
unsigned long cpu_cpsie(void);
|
#define INTERRUPTS_ENABLE() __enable_irq()
|
||||||
|
|
||||||
/** \brief Enables all CPU interrupts */
|
|
||||||
#define INTERRUPTS_ENABLE() cpu_cpsie()
|
|
||||||
|
|
||||||
/** \brief Disables all CPU interrupts. */
|
/** \brief Disables all CPU interrupts. */
|
||||||
#define INTERRUPTS_DISABLE() cpu_cpsid()
|
#define INTERRUPTS_DISABLE() __disable_irq()
|
||||||
|
|
||||||
#endif /* CPU_H_ */
|
#endif /* CPU_H_ */
|
||||||
|
|
||||||
|
|
|
@ -237,8 +237,8 @@ aes_auth_crypt_start(uint32_t ctrl, uint8_t key_area, const void *iv,
|
||||||
|
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
crypto_register_process_notification(process);
|
crypto_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_AES);
|
NVIC_ClearPendingIRQ(AES_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_AES);
|
NVIC_EnableIRQ(AES_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
if(data_len != 0) {
|
if(data_len != 0) {
|
||||||
|
@ -282,7 +282,7 @@ aes_auth_crypt_get_result(void *iv, void *tag)
|
||||||
AES_CTRL_INT_CLR_KEY_ST_WR_ERR |
|
AES_CTRL_INT_CLR_KEY_ST_WR_ERR |
|
||||||
AES_CTRL_INT_CLR_KEY_ST_RD_ERR;
|
AES_CTRL_INT_CLR_KEY_ST_RD_ERR;
|
||||||
|
|
||||||
nvic_interrupt_disable(NVIC_INT_AES);
|
NVIC_DisableIRQ(AES_IRQn);
|
||||||
crypto_register_process_notification(NULL);
|
crypto_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Disable the master control / DMA clock */
|
/* Disable the master control / DMA clock */
|
||||||
|
|
|
@ -130,8 +130,8 @@ bignum_mod_start(const uint32_t *number,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -158,7 +158,7 @@ bignum_mod_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -238,8 +238,8 @@ bignum_cmp_start(const uint32_t *number1,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -257,7 +257,7 @@ bignum_cmp_get_result(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Check the compare register. */
|
/* Check the compare register. */
|
||||||
|
@ -346,8 +346,8 @@ bignum_inv_mod_start(const uint32_t *number,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -374,7 +374,7 @@ bignum_inv_mod_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -469,8 +469,8 @@ bignum_mul_start(const uint32_t *multiplicand,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -498,7 +498,7 @@ bignum_mul_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -594,8 +594,8 @@ bignum_add_start(const uint32_t *number1,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -623,7 +623,7 @@ bignum_add_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -720,8 +720,8 @@ bignum_subtract_start(const uint32_t *number1,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -749,7 +749,7 @@ bignum_subtract_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -864,8 +864,8 @@ bignum_exp_mod_start(const uint32_t *number,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -892,7 +892,7 @@ bignum_exp_mod_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
@ -1000,8 +1000,8 @@ bignum_divide_start(const uint32_t *dividend,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -1029,7 +1029,7 @@ bignum_divide_get_result(uint32_t *buffer,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
/* Get the MSW register value. */
|
/* Get the MSW register value. */
|
||||||
|
|
|
@ -345,10 +345,10 @@ set_poll_mode(uint8_t enable)
|
||||||
mac_timer_init();
|
mac_timer_init();
|
||||||
REG(RFCORE_XREG_RFIRQM0) &= ~RFCORE_XREG_RFIRQM0_FIFOP; /* mask out FIFOP interrupt source */
|
REG(RFCORE_XREG_RFIRQM0) &= ~RFCORE_XREG_RFIRQM0_FIFOP; /* mask out FIFOP interrupt source */
|
||||||
REG(RFCORE_SFR_RFIRQF0) &= ~RFCORE_SFR_RFIRQF0_FIFOP; /* clear pending FIFOP interrupt */
|
REG(RFCORE_SFR_RFIRQF0) &= ~RFCORE_SFR_RFIRQF0_FIFOP; /* clear pending FIFOP interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_RF_RXTX); /* disable RF interrupts */
|
NVIC_DisableIRQ(RF_TX_RX_IRQn); /* disable RF interrupts */
|
||||||
} else {
|
} else {
|
||||||
REG(RFCORE_XREG_RFIRQM0) |= RFCORE_XREG_RFIRQM0_FIFOP; /* enable FIFOP interrupt source */
|
REG(RFCORE_XREG_RFIRQM0) |= RFCORE_XREG_RFIRQM0_FIFOP; /* enable FIFOP interrupt source */
|
||||||
nvic_interrupt_enable(NVIC_INT_RF_RXTX); /* enable RF interrupts */
|
NVIC_EnableIRQ(RF_TX_RX_IRQn); /* enable RF interrupts */
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
@ -516,7 +516,7 @@ init(void)
|
||||||
|
|
||||||
/* Acknowledge all RF Error interrupts */
|
/* Acknowledge all RF Error interrupts */
|
||||||
REG(RFCORE_XREG_RFERRM) = RFCORE_XREG_RFERRM_RFERRM;
|
REG(RFCORE_XREG_RFERRM) = RFCORE_XREG_RFERRM_RFERRM;
|
||||||
nvic_interrupt_enable(NVIC_INT_RF_ERR);
|
NVIC_EnableIRQ(RF_ERR_IRQn);
|
||||||
|
|
||||||
if(CC2538_RF_CONF_TX_USE_DMA) {
|
if(CC2538_RF_CONF_TX_USE_DMA) {
|
||||||
/* Disable peripheral triggers for the channel */
|
/* Disable peripheral triggers for the channel */
|
||||||
|
|
|
@ -61,8 +61,8 @@ crypto_isr(void)
|
||||||
{
|
{
|
||||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||||
|
|
||||||
nvic_interrupt_unpend(NVIC_INT_AES);
|
NVIC_ClearPendingIRQ(AES_IRQn);
|
||||||
nvic_interrupt_disable(NVIC_INT_AES);
|
NVIC_DisableIRQ(AES_IRQn);
|
||||||
|
|
||||||
if(notification_process != NULL) {
|
if(notification_process != NULL) {
|
||||||
process_poll((struct process *)notification_process);
|
process_poll((struct process *)notification_process);
|
||||||
|
|
|
@ -152,8 +152,8 @@ ecc_mul_start(uint32_t *scalar, ec_point_t *ec_point,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -181,7 +181,7 @@ ecc_mul_get_result(ec_point_t *ec_point,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
if(REG(PKA_SHIFT) == 0x00000000) {
|
if(REG(PKA_SHIFT) == 0x00000000) {
|
||||||
|
@ -319,8 +319,8 @@ ecc_mul_gen_pt_start(uint32_t *scalar, ecc_curve_info_t *curve,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -349,7 +349,7 @@ ecc_mul_gen_pt_get_result(ec_point_t *ec_point,
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
if(REG(PKA_SHIFT) == 0x00000000) {
|
if(REG(PKA_SHIFT) == 0x00000000) {
|
||||||
|
@ -492,8 +492,8 @@ ecc_add_start(ec_point_t *ec_point1, ec_point_t *ec_point2,
|
||||||
/* Enable Interrupt */
|
/* Enable Interrupt */
|
||||||
if(process != NULL) {
|
if(process != NULL) {
|
||||||
pka_register_process_notification(process);
|
pka_register_process_notification(process);
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_PKA);
|
NVIC_EnableIRQ(PKA_IRQn);
|
||||||
}
|
}
|
||||||
|
|
||||||
return PKA_STATUS_SUCCESS;
|
return PKA_STATUS_SUCCESS;
|
||||||
|
@ -519,7 +519,7 @@ ecc_add_get_result(ec_point_t *ec_point, uint32_t result_vector)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Disable Interrupt */
|
/* Disable Interrupt */
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
pka_register_process_notification(NULL);
|
pka_register_process_notification(NULL);
|
||||||
|
|
||||||
if(REG(PKA_SHIFT) == 0x00000000) {
|
if(REG(PKA_SHIFT) == 0x00000000) {
|
||||||
|
|
|
@ -1,68 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2012, Texas Instruments Incorporated - http://www.ti.com/
|
|
||||||
* 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 of the copyright holder 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 HOLDER 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.
|
|
||||||
*/
|
|
||||||
/**
|
|
||||||
* \addtogroup cc2538
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* \defgroup cc2538-mpu cc2538 Memory Protection Unit
|
|
||||||
*
|
|
||||||
* Driver for the cc2538 Memory Protection Unit
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* \file
|
|
||||||
* Header file for the ARM Memory Protection Unit
|
|
||||||
*/
|
|
||||||
#ifndef MPU_H_
|
|
||||||
#define MPU_H_
|
|
||||||
|
|
||||||
#define MPU_MPU_TYPE 0xE000ED90 /**< MPU Type */
|
|
||||||
#define MPU_MPU_CTRL 0xE000ED94 /**< MPU Control */
|
|
||||||
#define MPU_MPU_NUMBER 0xE000ED98 /**< MPU Region Number */
|
|
||||||
#define MPU_MPU_BASE 0xE000ED9C /**< MPU Region Base Address */
|
|
||||||
#define MPU_MPU_ATTR 0xE000EDA0 /**< MPU Region Attribute and Size */
|
|
||||||
#define MPU_MPU_BASE1 0xE000EDA4 /**< MPU Region Base Address Alias 1 */
|
|
||||||
#define MPU_MPU_ATTR1 0xE000EDA8 /**< MPU Region Attribute and Size Alias 1 */
|
|
||||||
#define MPU_MPU_BASE2 0xE000EDAC /**< MPU Region Base Address Alias 2 */
|
|
||||||
#define MPU_MPU_ATTR2 0xE000EDB0 /**< MPU Region Attribute and Size Alias 2*/
|
|
||||||
#define MPU_MPU_BASE3 0xE000EDB4 /**< MPU Region Base Address Alias 3 */
|
|
||||||
#define MPU_MPU_ATTR3 0xE000EDB8 /**< MPU Region Attribute and Size Alias 3*/
|
|
||||||
#define MPU_DBG_CTRL 0xE000EDF0 /**< Debug Control and Status Reg */
|
|
||||||
#define MPU_DBG_XFER 0xE000EDF4 /**< Debug Core Reg. Transfer Select */
|
|
||||||
#define MPU_DBG_DATA 0xE000EDF8 /**< Debug Core Register Data */
|
|
||||||
#define MPU_DBG_INT 0xE000EDFC /**< Debug Reset Interrupt Control */
|
|
||||||
#define MPU_SW_TRIG 0xE000EF00 /**< Software Trigger Interrupt */
|
|
||||||
|
|
||||||
#endif /* MPU_H_ */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
|
@ -38,74 +38,12 @@
|
||||||
*/
|
*/
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "dev/nvic.h"
|
#include "dev/nvic.h"
|
||||||
#include "dev/scb.h"
|
#include "cc2538_cm3.h"
|
||||||
#include "reg.h"
|
|
||||||
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
static uint32_t *interrupt_enable;
|
|
||||||
static uint32_t *interrupt_disable;
|
|
||||||
static uint32_t *interrupt_pend;
|
|
||||||
static uint32_t *interrupt_unpend;
|
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
nvic_init()
|
nvic_init()
|
||||||
{
|
{
|
||||||
interrupt_enable = (uint32_t *)NVIC_EN0;
|
|
||||||
interrupt_disable = (uint32_t *)NVIC_DIS0;
|
|
||||||
interrupt_pend = (uint32_t *)NVIC_PEND0;
|
|
||||||
interrupt_unpend = (uint32_t *)NVIC_UNPEND0;
|
|
||||||
|
|
||||||
/* Provide our interrupt table to the NVIC */
|
/* Provide our interrupt table to the NVIC */
|
||||||
REG(SCB_VTABLE) = NVIC_VTABLE_ADDRESS;
|
SCB->VTOR = NVIC_VTABLE_ADDRESS;
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
void
|
|
||||||
nvic_interrupt_enable(uint32_t intr)
|
|
||||||
{
|
|
||||||
/* Writes of 0 are ignored, which is why we can simply use = */
|
|
||||||
interrupt_enable[intr >> 5] = 1 << (intr & 0x1F);
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
void
|
|
||||||
nvic_interrupt_disable(uint32_t intr)
|
|
||||||
{
|
|
||||||
/* Writes of 0 are ignored, which is why we can simply use = */
|
|
||||||
interrupt_disable[intr >> 5] = 1 << (intr & 0x1F);
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
void
|
|
||||||
nvic_interrupt_en_restore(uint32_t intr, uint8_t v)
|
|
||||||
{
|
|
||||||
if(v != 1) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
interrupt_enable[intr >> 5] = 1 << (intr & 0x1F);
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
uint8_t
|
|
||||||
nvic_interrupt_en_save(uint32_t intr)
|
|
||||||
{
|
|
||||||
uint8_t rv = ((interrupt_enable[intr >> 5] & (1 << (intr & 0x1F)))
|
|
||||||
> NVIC_INTERRUPT_DISABLED);
|
|
||||||
|
|
||||||
nvic_interrupt_disable(intr);
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
void
|
|
||||||
nvic_interrupt_pend(uint32_t intr)
|
|
||||||
{
|
|
||||||
/* Writes of 0 are ignored, which is why we can simply use = */
|
|
||||||
interrupt_pend[intr >> 5] = 1 << (intr & 0x1F);
|
|
||||||
}
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
void
|
|
||||||
nvic_interrupt_unpend(uint32_t intr)
|
|
||||||
{
|
|
||||||
/* Writes of 0 are ignored, which is why we can simply use = */
|
|
||||||
interrupt_unpend[intr >> 5] = 1 << (intr & 0x1F);
|
|
||||||
}
|
}
|
||||||
/** @} */
|
/** @} */
|
||||||
|
|
|
@ -43,14 +43,13 @@
|
||||||
#ifndef NVIC_H_
|
#ifndef NVIC_H_
|
||||||
#define NVIC_H_
|
#define NVIC_H_
|
||||||
|
|
||||||
|
#include "cc2538_cm3.h"
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/** \name NVIC Constants and Configuration
|
/** \name NVIC Constants and Configuration
|
||||||
* @{
|
* @{
|
||||||
*/
|
*/
|
||||||
#define NVIC_INTERRUPT_ENABLED 0x00000001
|
|
||||||
#define NVIC_INTERRUPT_DISABLED 0x00000000
|
|
||||||
|
|
||||||
#ifdef NVIC_CONF_VTABLE_ADDRESS
|
#ifdef NVIC_CONF_VTABLE_ADDRESS
|
||||||
#define NVIC_VTABLE_ADDRESS NVIC_CONF_VTABLE_ADDRESS
|
#define NVIC_VTABLE_ADDRESS NVIC_CONF_VTABLE_ADDRESS
|
||||||
#else
|
#else
|
||||||
|
@ -59,183 +58,9 @@ extern void(*const vectors[])(void);
|
||||||
#endif
|
#endif
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/** \name NVIC Interrupt assignments
|
|
||||||
* @{
|
|
||||||
*/
|
|
||||||
#define NVIC_INT_GPIO_PORT_A 0 /**< GPIO port A */
|
|
||||||
#define NVIC_INT_GPIO_PORT_B 1 /**< GPIO port B */
|
|
||||||
#define NVIC_INT_GPIO_PORT_C 2 /**< GPIO port C */
|
|
||||||
#define NVIC_INT_GPIO_PORT_D 3 /**< GPIO port D */
|
|
||||||
#define NVIC_INT_UART0 5 /**< UART0 */
|
|
||||||
#define NVIC_INT_UART1 6 /**< UART1 */
|
|
||||||
#define NVIC_INT_SSI0 7 /**< SSI0 */
|
|
||||||
#define NVIC_INT_I2C 8 /**< I2C */
|
|
||||||
#define NVIC_INT_ADC 14 /**< ADC */
|
|
||||||
#define NVIC_INT_WDT 18 /**< Watchdog Timer */
|
|
||||||
#define NVIC_INT_GPTIMER_0A 19 /**< GPTimer 0A */
|
|
||||||
#define NVIC_INT_GPTIMER_0B 20 /**< GPTimer 0B */
|
|
||||||
#define NVIC_INT_GPTIMER_1A 21 /**< GPTimer 1A */
|
|
||||||
#define NVIC_INT_GPTIMER_1B 22 /**< GPTimer 1B */
|
|
||||||
#define NVIC_INT_GPTIMER_2A 23 /**< GPTimer 2A */
|
|
||||||
#define NVIC_INT_GPTIMER_2B 24 /**< GPTimer 2B */
|
|
||||||
#define NVIC_INT_ADC_CMP 25 /**< Analog Comparator */
|
|
||||||
#define NVIC_INT_RF_RXTX_ALT 26 /**< RF TX/RX (Alternate) */
|
|
||||||
#define NVIC_INT_RF_ERR_ALT 27 /**< RF Error (Alternate) */
|
|
||||||
#define NVIC_INT_SYS_CTRL 28 /**< System Control */
|
|
||||||
#define NVIC_INT_FLASH_CTRL 29 /**< Flash memory control */
|
|
||||||
#define NVIC_INT_AES_ALT 30 /**< AES (Alternate) */
|
|
||||||
#define NVIC_INT_PKA_ALT 31 /**< PKA (Alternate) */
|
|
||||||
#define NVIC_INT_SM_TIMER_ALT 32 /**< SM Timer (Alternate) */
|
|
||||||
#define NVIC_INT_MAC_TIMER_ALT 33 /**< MAC Timer (Alternate) */
|
|
||||||
#define NVIC_INT_SSI1 34 /**< SSI1 */
|
|
||||||
#define NVIC_INT_GPTIMER_3A 35 /**< GPTimer 3A */
|
|
||||||
#define NVIC_INT_GPTIMER_3B 36 /**< GPTimer 3B */
|
|
||||||
#define NVIC_INT_UDMA 46 /**< uDMA software */
|
|
||||||
#define NVIC_INT_UDMA_ERR 47 /**< uDMA error */
|
|
||||||
#define NVIC_INT_USB 140 /**< USB */
|
|
||||||
#define NVIC_INT_RF_RXTX 141 /**< RF Core Rx/Tx */
|
|
||||||
#define NVIC_INT_RF_ERR 142 /**< RF Core Error */
|
|
||||||
#define NVIC_INT_AES 143 /**< AES */
|
|
||||||
#define NVIC_INT_PKA 144 /**< PKA */
|
|
||||||
#define NVIC_INT_SM_TIMER 145 /**< SM Timer */
|
|
||||||
#define NVIC_INT_MACTIMER 146 /**< MAC Timer */
|
|
||||||
/** @} */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/** \name NVIC Register Declarations
|
|
||||||
* @{
|
|
||||||
*/
|
|
||||||
#define NVIC_EN0 0xE000E100 /**< Interrupt 0-31 Set Enable */
|
|
||||||
#define NVIC_EN1 0xE000E104 /**< Interrupt 32-54 Set Enable */
|
|
||||||
#define NVIC_EN2 0xE000E108 /**< Interrupt 64-95 Set Enable */
|
|
||||||
#define NVIC_EN3 0xE000E10C /**< Interrupt 96-127 Set Enable */
|
|
||||||
#define NVIC_EN4 0xE000E110 /**< Interrupt 128-131 Set Enable */
|
|
||||||
#define NVIC_DIS0 0xE000E180 /**< Interrupt 0-31 Clear Enable */
|
|
||||||
#define NVIC_DIS1 0xE000E184 /**< Interrupt 32-54 Clear Enable */
|
|
||||||
#define NVIC_DIS2 0xE000E188 /**< Interrupt 64-95 Clear Enable */
|
|
||||||
#define NVIC_DIS3 0xE000E18C /**< Interrupt 96-127 Clear Enable */
|
|
||||||
#define NVIC_DIS4 0xE000E190 /**< Interrupt 128-131 Clear Enable */
|
|
||||||
#define NVIC_PEND0 0xE000E200 /**< Interrupt 0-31 Set Pending */
|
|
||||||
#define NVIC_PEND1 0xE000E204 /**< Interrupt 32-54 Set Pending */
|
|
||||||
#define NVIC_PEND2 0xE000E208 /**< Interrupt 64-95 Set Pending */
|
|
||||||
#define NVIC_PEND3 0xE000E20C /**< Interrupt 96-127 Set Pending */
|
|
||||||
#define NVIC_PEND4 0xE000E210 /**< Interrupt 128-131 Set Pending */
|
|
||||||
#define NVIC_UNPEND0 0xE000E280 /**< Interrupt 0-31 Clear Pending */
|
|
||||||
#define NVIC_UNPEND1 0xE000E284 /**< Interrupt 32-54 Clear Pending */
|
|
||||||
#define NVIC_UNPEND2 0xE000E288 /**< Interrupt 64-95 Clear Pending */
|
|
||||||
#define NVIC_UNPEND3 0xE000E28C /**< Interrupt 96-127 Clear Pending */
|
|
||||||
#define NVIC_UNPEND4 0xE000E290 /**< Interrupt 128-131 Clear Pending */
|
|
||||||
#define NVIC_ACTIVE0 0xE000E300 /**< Interrupt 0-31 Active Bit */
|
|
||||||
#define NVIC_ACTIVE1 0xE000E304 /**< Interrupt 32-54 Active Bit */
|
|
||||||
#define NVIC_ACTIVE2 0xE000E308 /**< Interrupt 64-95 Active Bit */
|
|
||||||
#define NVIC_ACTIVE3 0xE000E30C /**< Interrupt 96-127 Active Bit */
|
|
||||||
#define NVIC_ACTIVE4 0xE000E310 /**< Interrupt 128-131 Active Bit */
|
|
||||||
#define NVIC_PRI0 0xE000E400 /**< Interrupt 0-3 Priority */
|
|
||||||
#define NVIC_PRI1 0xE000E404 /**< Interrupt 4-7 Priority */
|
|
||||||
#define NVIC_PRI2 0xE000E408 /**< Interrupt 8-11 Priority */
|
|
||||||
#define NVIC_PRI3 0xE000E40C /**< Interrupt 12-15 Priority */
|
|
||||||
#define NVIC_PRI4 0xE000E410 /**< Interrupt 16-19 Priority */
|
|
||||||
#define NVIC_PRI5 0xE000E414 /**< Interrupt 20-23 Priority */
|
|
||||||
#define NVIC_PRI6 0xE000E418 /**< Interrupt 24-27 Priority */
|
|
||||||
#define NVIC_PRI7 0xE000E41C /**< Interrupt 28-31 Priority */
|
|
||||||
#define NVIC_PRI8 0xE000E420 /**< Interrupt 32-35 Priority */
|
|
||||||
#define NVIC_PRI9 0xE000E424 /**< Interrupt 36-39 Priority */
|
|
||||||
#define NVIC_PRI10 0xE000E428 /**< Interrupt 40-43 Priority */
|
|
||||||
#define NVIC_PRI11 0xE000E42C /**< Interrupt 44-47 Priority */
|
|
||||||
#define NVIC_PRI12 0xE000E430 /**< Interrupt 48-51 Priority */
|
|
||||||
#define NVIC_PRI13 0xE000E434 /**< Interrupt 52-53 Priority */
|
|
||||||
#define NVIC_PRI14 0xE000E438 /**< Interrupt 56-59 Priority */
|
|
||||||
#define NVIC_PRI15 0xE000E43C /**< Interrupt 60-63 Priority */
|
|
||||||
#define NVIC_PRI16 0xE000E440 /**< Interrupt 64-67 Priority */
|
|
||||||
#define NVIC_PRI17 0xE000E444 /**< Interrupt 68-71 Priority */
|
|
||||||
#define NVIC_PRI18 0xE000E448 /**< Interrupt 72-75 Priority */
|
|
||||||
#define NVIC_PRI19 0xE000E44C /**< Interrupt 76-79 Priority */
|
|
||||||
#define NVIC_PRI20 0xE000E450 /**< Interrupt 80-83 Priority */
|
|
||||||
#define NVIC_PRI21 0xE000E454 /**< Interrupt 84-87 Priority */
|
|
||||||
#define NVIC_PRI22 0xE000E458 /**< Interrupt 88-91 Priority */
|
|
||||||
#define NVIC_PRI23 0xE000E45C /**< Interrupt 92-95 Priority */
|
|
||||||
#define NVIC_PRI24 0xE000E460 /**< Interrupt 96-99 Priority */
|
|
||||||
#define NVIC_PRI25 0xE000E464 /**< Interrupt 100-103 Priority */
|
|
||||||
#define NVIC_PRI26 0xE000E468 /**< Interrupt 104-107 Priority */
|
|
||||||
#define NVIC_PRI27 0xE000E46C /**< Interrupt 108-111 Priority */
|
|
||||||
#define NVIC_PRI28 0xE000E470 /**< Interrupt 112-115 Priority */
|
|
||||||
#define NVIC_PRI29 0xE000E474 /**< Interrupt 116-119 Priority */
|
|
||||||
#define NVIC_PRI30 0xE000E478 /**< Interrupt 120-123 Priority */
|
|
||||||
#define NVIC_PRI31 0xE000E47C /**< Interrupt 124-127 Priority */
|
|
||||||
#define NVIC_PRI32 0xE000E480 /**< Interrupt 128-131 Priority */
|
|
||||||
#define NVIC_PRI33 0xE000E480 /**< Interrupt 132-135 Priority */
|
|
||||||
#define NVIC_PRI34 0xE000E484 /**< Interrupt 136-139 Priority */
|
|
||||||
#define NVIC_PRI35 0xE000E488 /**< Interrupt 140-143 Priority */
|
|
||||||
#define NVIC_PRI36 0xE000E48c /**< Interrupt 144-147 Priority */
|
|
||||||
/** @} */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/** \brief Initialises the NVIC driver */
|
/** \brief Initialises the NVIC driver */
|
||||||
void nvic_init();
|
void nvic_init();
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Enables interrupt intr
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
*
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to enable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
void nvic_interrupt_enable(uint32_t intr);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Disables interrupt intr
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
*
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
void nvic_interrupt_disable(uint32_t intr);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Enables interrupt intr if v > 0
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
* \param v 0: No effect, 1: Enables the interrupt
|
|
||||||
*
|
|
||||||
* This function is useful to restore an interrupt to a state previously
|
|
||||||
* saved by nvic_interrupt_en_save. Thus, if when nvic_interrupt_en_save was
|
|
||||||
* called the interrupt was enabled, this function will re-enabled it.
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
void nvic_interrupt_en_restore(uint32_t intr, uint8_t v);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Checks the interrupt enabled status for intr
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
* \return 1: Enabled, 0: Disabled
|
|
||||||
*
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
uint8_t nvic_interrupt_en_save(uint32_t intr);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Sets intr to pending
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
*
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to enable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
void nvic_interrupt_pend(uint32_t intr);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* \brief Sets intr to no longer pending
|
|
||||||
* \param intr The interrupt number (NOT the vector number). For example,
|
|
||||||
* GPIO Port A interrupt is 0, not 16.
|
|
||||||
*
|
|
||||||
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
|
|
||||||
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
|
|
||||||
*/
|
|
||||||
void nvic_interrupt_unpend(uint32_t intr);
|
|
||||||
|
|
||||||
#endif /* NVIC_H_ */
|
#endif /* NVIC_H_ */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -64,8 +64,8 @@ pka_isr(void)
|
||||||
{
|
{
|
||||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||||
|
|
||||||
nvic_interrupt_unpend(NVIC_INT_PKA);
|
NVIC_ClearPendingIRQ(PKA_IRQn);
|
||||||
nvic_interrupt_disable(NVIC_INT_PKA);
|
NVIC_DisableIRQ(PKA_IRQn);
|
||||||
|
|
||||||
if(notification_process != NULL) {
|
if(notification_process != NULL) {
|
||||||
process_poll((struct process *)notification_process);
|
process_poll((struct process *)notification_process);
|
||||||
|
|
|
@ -1,83 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2012, Texas Instruments Incorporated - http://www.ti.com/
|
|
||||||
* 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 of the copyright holder 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 HOLDER 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.
|
|
||||||
*/
|
|
||||||
/**
|
|
||||||
* \addtogroup cc2538
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* \defgroup cc2538-scb cc2538 System Control Block (SCB)
|
|
||||||
*
|
|
||||||
* Offsets and bit definitions for SCB registers
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* \file
|
|
||||||
* Header file for the System Control Block (SCB)
|
|
||||||
*/
|
|
||||||
#ifndef SCB_H_
|
|
||||||
#define SCB_H_
|
|
||||||
|
|
||||||
#define SCB_CPUID 0xE000ED00 /**< CPU ID Base */
|
|
||||||
#define SCB_INTCTRL 0xE000ED04 /**< Interrupt Control and State */
|
|
||||||
#define SCB_VTABLE 0xE000ED08 /**< Vector Table Offset */
|
|
||||||
#define SCB_APINT 0xE000ED0C /**< Application Interrupt and Reset Control */
|
|
||||||
#define SCB_SYSCTRL 0xE000ED10 /**< System Control */
|
|
||||||
#define SCB_CFGCTRL 0xE000ED14 /**< Configuration and Control */
|
|
||||||
#define SCB_SYSPRI1 0xE000ED18 /**< System Handler Priority 1 */
|
|
||||||
#define SCB_SYSPRI2 0xE000ED1C /**< System Handler Priority 2 */
|
|
||||||
#define SCB_SYSPRI3 0xE000ED20 /**< System Handler Priority 3 */
|
|
||||||
#define SCB_SYSHNDCTRL 0xE000ED24 /**< System Handler Control and State */
|
|
||||||
#define SCB_FAULTSTAT 0xE000ED28 /**< Configurable Fault Status */
|
|
||||||
#define SCB_HFAULTSTAT 0xE000ED2C /**< Hard Fault Status */
|
|
||||||
#define SCB_DEBUG_STAT 0xE000ED30 /**< Debug Status Register */
|
|
||||||
#define SCB_MMADDR 0xE000ED34 /**< Memory Management Fault Address */
|
|
||||||
#define SCB_FAULT_ADDR 0xE000ED38 /**< Bus Fault Address */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/** \name VTABLE register bits
|
|
||||||
* @{
|
|
||||||
*/
|
|
||||||
#define SCB_VTABLE_BASE 0x20000000 /**< Vector Table Base */
|
|
||||||
#define SCB_VTABLE_OFFSET_M 0x1FFFFE00 /**< Vector Table Offset */
|
|
||||||
/** @} */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/** \name SCB_SYSCTRL register bits
|
|
||||||
* @{
|
|
||||||
*/
|
|
||||||
#define SCB_SYSCTRL_SEVONPEND 0x00000010 /**< Wake up on pending */
|
|
||||||
#define SCB_SYSCTRL_SLEEPDEEP 0x00000004 /**< Deep sleep enable */
|
|
||||||
#define SCB_SYSCTRL_SLEEPEXIT 0x00000002 /**< Sleep on ISR exit */
|
|
||||||
/** @} */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
|
|
||||||
#endif /* SCB_H_ */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
|
@ -1,53 +0,0 @@
|
||||||
/*
|
|
||||||
* Copyright (c) 2012, Texas Instruments Incorporated - http:/www.ti.com/
|
|
||||||
* 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 of the copyright holder 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 HOLDER 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.
|
|
||||||
*/
|
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* Header for with definitions related to the cc2538 SysTick
|
|
||||||
*/
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
#ifndef SYSTICK_H_
|
|
||||||
#define SYSTICK_H_
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/* SysTick Register Definitions */
|
|
||||||
#define SYSTICK_STCTRL 0xE000E010 /* Control and Status */
|
|
||||||
#define SYSTICK_STRELOAD 0xE000E014 /* Reload Value */
|
|
||||||
#define SYSTICK_STCURRENT 0xE000E018 /* Current Value */
|
|
||||||
#define SYSTICK_STCAL 0xE000E01C /* SysTick Calibration */
|
|
||||||
/*---------------------------------------------------------------------------*/
|
|
||||||
/* Bit Definitions for the STCTRL Register */
|
|
||||||
#define SYSTICK_STCTRL_COUNT 0x00010000 /* Count Flag */
|
|
||||||
#define SYSTICK_STCTRL_CLK_SRC 0x00000004 /* Clock Source */
|
|
||||||
#define SYSTICK_STCTRL_INTEN 0x00000002 /* Interrupt Enable */
|
|
||||||
#define SYSTICK_STCTRL_ENABLE 0x00000001 /* Enable */
|
|
||||||
|
|
||||||
#endif /* SYSTICK_H_ */
|
|
||||||
|
|
||||||
/** @} */
|
|
|
@ -181,7 +181,7 @@ static const uart_regs_t uart_regs[UART_INSTANCE_COUNT] = {
|
||||||
.tx = {UART0_TX_PORT, UART0_TX_PIN},
|
.tx = {UART0_TX_PORT, UART0_TX_PIN},
|
||||||
.cts = {-1, -1},
|
.cts = {-1, -1},
|
||||||
.rts = {-1, -1},
|
.rts = {-1, -1},
|
||||||
.nvic_int = NVIC_INT_UART0
|
.nvic_int = UART0_IRQn
|
||||||
}, {
|
}, {
|
||||||
.sys_ctrl_rcgcuart_uart = SYS_CTRL_RCGCUART_UART1,
|
.sys_ctrl_rcgcuart_uart = SYS_CTRL_RCGCUART_UART1,
|
||||||
.sys_ctrl_scgcuart_uart = SYS_CTRL_SCGCUART_UART1,
|
.sys_ctrl_scgcuart_uart = SYS_CTRL_SCGCUART_UART1,
|
||||||
|
@ -195,7 +195,7 @@ static const uart_regs_t uart_regs[UART_INSTANCE_COUNT] = {
|
||||||
.tx = {UART1_TX_PORT, UART1_TX_PIN},
|
.tx = {UART1_TX_PORT, UART1_TX_PIN},
|
||||||
.cts = {UART1_CTS_PORT, UART1_CTS_PIN},
|
.cts = {UART1_CTS_PORT, UART1_CTS_PIN},
|
||||||
.rts = {UART1_RTS_PORT, UART1_RTS_PIN},
|
.rts = {UART1_RTS_PORT, UART1_RTS_PIN},
|
||||||
.nvic_int = NVIC_INT_UART1
|
.nvic_int = UART1_IRQn
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
static int (* input_handler[UART_INSTANCE_COUNT])(unsigned char c);
|
static int (* input_handler[UART_INSTANCE_COUNT])(unsigned char c);
|
||||||
|
@ -328,7 +328,7 @@ uart_init(uint8_t uart)
|
||||||
REG(regs->base + UART_CTL) |= UART_CTL_UARTEN;
|
REG(regs->base + UART_CTL) |= UART_CTL_UARTEN;
|
||||||
|
|
||||||
/* Enable UART0 Interrupts */
|
/* Enable UART0 Interrupts */
|
||||||
nvic_interrupt_enable(regs->nvic_int);
|
NVIC_EnableIRQ(regs->nvic_int);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
|
|
@ -62,8 +62,8 @@ udma_init()
|
||||||
|
|
||||||
REG(UDMA_CTLBASE) = (uint32_t)(&channel_config);
|
REG(UDMA_CTLBASE) = (uint32_t)(&channel_config);
|
||||||
|
|
||||||
nvic_interrupt_enable(NVIC_INT_UDMA);
|
NVIC_EnableIRQ(UDMA_SW_IRQn);
|
||||||
nvic_interrupt_enable(NVIC_INT_UDMA_ERR);
|
NVIC_EnableIRQ(UDMA_ERR_IRQn);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
|
|
@ -39,10 +39,10 @@
|
||||||
#include "sys/energest.h"
|
#include "sys/energest.h"
|
||||||
#include "sys/process.h"
|
#include "sys/process.h"
|
||||||
#include "dev/sys-ctrl.h"
|
#include "dev/sys-ctrl.h"
|
||||||
#include "dev/scb.h"
|
|
||||||
#include "dev/rfcore-xreg.h"
|
#include "dev/rfcore-xreg.h"
|
||||||
#include "rtimer-arch.h"
|
#include "rtimer-arch.h"
|
||||||
#include "lpm.h"
|
#include "lpm.h"
|
||||||
|
#include "cc2538_cm3.h"
|
||||||
#include "reg.h"
|
#include "reg.h"
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
@ -379,7 +379,7 @@ lpm_init()
|
||||||
* By default, we will enter PM0 unless lpm_enter() decides otherwise
|
* By default, we will enter PM0 unless lpm_enter() decides otherwise
|
||||||
*/
|
*/
|
||||||
REG(SYS_CTRL_PMCTL) = SYS_CTRL_PMCTL_PM0;
|
REG(SYS_CTRL_PMCTL) = SYS_CTRL_PMCTL_PM0;
|
||||||
REG(SCB_SYSCTRL) |= SCB_SYSCTRL_SLEEPDEEP;
|
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
|
||||||
|
|
||||||
max_pm = LPM_CONF_MAX_PM;
|
max_pm = LPM_CONF_MAX_PM;
|
||||||
|
|
||||||
|
|
|
@ -99,7 +99,7 @@ rtimer_arch_schedule(rtimer_clock_t t)
|
||||||
/* Store the value. The LPM module will query us for it */
|
/* Store the value. The LPM module will query us for it */
|
||||||
next_trigger = t;
|
next_trigger = t;
|
||||||
|
|
||||||
nvic_interrupt_enable(NVIC_INT_SM_TIMER);
|
NVIC_EnableIRQ(SMT_IRQn);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
rtimer_clock_t
|
rtimer_clock_t
|
||||||
|
@ -147,8 +147,8 @@ rtimer_isr()
|
||||||
|
|
||||||
next_trigger = 0;
|
next_trigger = 0;
|
||||||
|
|
||||||
nvic_interrupt_unpend(NVIC_INT_SM_TIMER);
|
NVIC_ClearPendingIRQ(SMT_IRQn);
|
||||||
nvic_interrupt_disable(NVIC_INT_SM_TIMER);
|
NVIC_DisableIRQ(SMT_IRQn);
|
||||||
|
|
||||||
rtimer_run_next();
|
rtimer_run_next();
|
||||||
|
|
||||||
|
|
|
@ -167,6 +167,24 @@ static void in_ep_interrupt_handler(uint8_t ep_hw);
|
||||||
static void out_ep_interrupt_handler(uint8_t ep_hw);
|
static void out_ep_interrupt_handler(uint8_t ep_hw);
|
||||||
static void ep0_interrupt_handler(void);
|
static void ep0_interrupt_handler(void);
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static uint8_t
|
||||||
|
disable_irq(void)
|
||||||
|
{
|
||||||
|
uint8_t enabled = NVIC_IsIRQEnabled(USB_IRQn);
|
||||||
|
if(enabled) {
|
||||||
|
NVIC_DisableIRQ(USB_IRQn);
|
||||||
|
}
|
||||||
|
return enabled;
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static void
|
||||||
|
restore_irq(uint8_t enabled)
|
||||||
|
{
|
||||||
|
if(enabled) {
|
||||||
|
NVIC_EnableIRQ(USB_IRQn);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
static void
|
static void
|
||||||
notify_process(unsigned int e)
|
notify_process(unsigned int e)
|
||||||
{
|
{
|
||||||
|
@ -205,12 +223,12 @@ usb_arch_get_global_events(void)
|
||||||
uint8_t flag;
|
uint8_t flag;
|
||||||
volatile unsigned int e;
|
volatile unsigned int e;
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
e = events;
|
e = events;
|
||||||
events = 0;
|
events = 0;
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
|
|
||||||
return e;
|
return e;
|
||||||
}
|
}
|
||||||
|
@ -222,12 +240,12 @@ usb_get_ep_events(uint8_t addr)
|
||||||
uint8_t flag;
|
uint8_t flag;
|
||||||
usb_endpoint_t *ep = EP_STRUCT(addr);
|
usb_endpoint_t *ep = EP_STRUCT(addr);
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
e = ep->events;
|
e = ep->events;
|
||||||
ep->events = 0;
|
ep->events = 0;
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
|
|
||||||
return e;
|
return e;
|
||||||
}
|
}
|
||||||
|
@ -360,7 +378,7 @@ usb_arch_setup(void)
|
||||||
udma_channel_mask_set(USB_ARCH_CONF_TX_DMA_CHAN);
|
udma_channel_mask_set(USB_ARCH_CONF_TX_DMA_CHAN);
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_enable(NVIC_INT_USB);
|
NVIC_EnableIRQ(USB_IRQn);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -381,7 +399,7 @@ usb_submit_recv_buffer(uint8_t addr, usb_buffer *buffer)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
tailp = &ep->buffer;
|
tailp = &ep->buffer;
|
||||||
while(*tailp) {
|
while(*tailp) {
|
||||||
|
@ -404,7 +422,7 @@ usb_submit_recv_buffer(uint8_t addr, usb_buffer *buffer)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -419,7 +437,7 @@ usb_submit_xmit_buffer(uint8_t addr, usb_buffer *buffer)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
if(EP_HW_NUM(addr) == 0) {
|
if(EP_HW_NUM(addr) == 0) {
|
||||||
if(buffer->data == NULL) {
|
if(buffer->data == NULL) {
|
||||||
|
@ -429,7 +447,7 @@ usb_submit_xmit_buffer(uint8_t addr, usb_buffer *buffer)
|
||||||
REG(USB_INDEX) = 0;
|
REG(USB_INDEX) = 0;
|
||||||
REG(USB_CS0) = USB_CS0_CLR_OUTPKT_RDY | USB_CS0_DATA_END;
|
REG(USB_CS0) = USB_CS0_CLR_OUTPKT_RDY | USB_CS0_DATA_END;
|
||||||
notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION);
|
notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION);
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
/* Release the HW FIFO */
|
/* Release the HW FIFO */
|
||||||
|
@ -455,7 +473,7 @@ usb_submit_xmit_buffer(uint8_t addr, usb_buffer *buffer)
|
||||||
res = ep0_tx();
|
res = ep0_tx();
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
|
|
||||||
if(res & USB_WRITE_NOTIFY) {
|
if(res & USB_WRITE_NOTIFY) {
|
||||||
notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION);
|
notify_ep_process(ep, USB_EP_EVENT_NOTIFICATION);
|
||||||
|
@ -520,7 +538,7 @@ ep_setup(uint8_t addr)
|
||||||
ep->events = 0;
|
ep->events = 0;
|
||||||
ep->xfer_size = ep_xfer_size[ei];
|
ep->xfer_size = ep_xfer_size[ei];
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
/* Select endpoint register */
|
/* Select endpoint register */
|
||||||
REG(USB_INDEX) = ei;
|
REG(USB_INDEX) = ei;
|
||||||
|
@ -536,7 +554,7 @@ ep_setup(uint8_t addr)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -616,7 +634,7 @@ usb_arch_disable_endpoint(uint8_t addr)
|
||||||
|
|
||||||
ep->flags &= ~USB_EP_FLAGS_ENABLED;
|
ep->flags &= ~USB_EP_FLAGS_ENABLED;
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
REG(USB_INDEX) = ei;
|
REG(USB_INDEX) = ei;
|
||||||
if(ei == 0) {
|
if(ei == 0) {
|
||||||
|
@ -628,7 +646,7 @@ usb_arch_disable_endpoint(uint8_t addr)
|
||||||
out_ep_dis(addr);
|
out_ep_dis(addr);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -638,11 +656,11 @@ usb_arch_discard_all_buffers(uint8_t addr)
|
||||||
uint8_t flag;
|
uint8_t flag;
|
||||||
volatile usb_endpoint_t *ep = EP_STRUCT(addr);
|
volatile usb_endpoint_t *ep = EP_STRUCT(addr);
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
buffer = ep->buffer;
|
buffer = ep->buffer;
|
||||||
ep->buffer = NULL;
|
ep->buffer = NULL;
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
|
|
||||||
while(buffer) {
|
while(buffer) {
|
||||||
buffer->flags &= ~USB_BUFFER_SUBMITTED;
|
buffer->flags &= ~USB_BUFFER_SUBMITTED;
|
||||||
|
@ -689,11 +707,11 @@ usb_arch_control_stall(uint8_t addr)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
set_stall(addr, 1);
|
set_stall(addr, 1);
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -711,7 +729,7 @@ usb_arch_halt_endpoint(uint8_t addr, int halt)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
if(halt) {
|
if(halt) {
|
||||||
ep->halted = 0x1;
|
ep->halted = 0x1;
|
||||||
|
@ -732,7 +750,7 @@ usb_arch_halt_endpoint(uint8_t addr, int halt)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -767,7 +785,7 @@ usb_arch_send_pending(uint8_t addr)
|
||||||
uint8_t ret;
|
uint8_t ret;
|
||||||
uint8_t ei = EP_INDEX(addr);
|
uint8_t ei = EP_INDEX(addr);
|
||||||
|
|
||||||
flag = nvic_interrupt_en_save(NVIC_INT_USB);
|
flag = disable_irq();
|
||||||
|
|
||||||
REG(USB_INDEX) = ei;
|
REG(USB_INDEX) = ei;
|
||||||
if(ei == 0) {
|
if(ei == 0) {
|
||||||
|
@ -776,7 +794,7 @@ usb_arch_send_pending(uint8_t addr)
|
||||||
ret = REG(USB_CSIL) & USB_CSIL_INPKT_RDY;
|
ret = REG(USB_CSIL) & USB_CSIL_INPKT_RDY;
|
||||||
}
|
}
|
||||||
|
|
||||||
nvic_interrupt_en_restore(NVIC_INT_USB, flag);
|
restore_irq(flag);
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
|
@ -50,7 +50,6 @@
|
||||||
#include "dev/watchdog.h"
|
#include "dev/watchdog.h"
|
||||||
#include "dev/sys-ctrl.h"
|
#include "dev/sys-ctrl.h"
|
||||||
#include "pwm.h"
|
#include "pwm.h"
|
||||||
#include "systick.h"
|
|
||||||
#include "lpm.h"
|
#include "lpm.h"
|
||||||
#include "dev/ioc.h"
|
#include "dev/ioc.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
|
@ -152,7 +152,7 @@ PROCESS_THREAD(cc2538_demo_process, ev, data)
|
||||||
} else if(data == &button_left_sensor || data == &button_right_sensor) {
|
} else if(data == &button_left_sensor || data == &button_right_sensor) {
|
||||||
leds_toggle(LEDS_BUTTON);
|
leds_toggle(LEDS_BUTTON);
|
||||||
} else if(data == &button_down_sensor) {
|
} else if(data == &button_down_sensor) {
|
||||||
cpu_cpsid();
|
INTERRUPTS_DISABLE();
|
||||||
leds_on(LEDS_REBOOT);
|
leds_on(LEDS_REBOOT);
|
||||||
watchdog_reboot();
|
watchdog_reboot();
|
||||||
} else if(data == &button_up_sensor) {
|
} else if(data == &button_up_sensor) {
|
||||||
|
|
|
@ -48,7 +48,7 @@
|
||||||
*/
|
*/
|
||||||
#define MOTION_SENSOR_PORT GPIO_A_NUM
|
#define MOTION_SENSOR_PORT GPIO_A_NUM
|
||||||
#define MOTION_SENSOR_PIN 5
|
#define MOTION_SENSOR_PIN 5
|
||||||
#define MOTION_SENSOR_VECTOR NVIC_INT_GPIO_PORT_A
|
#define MOTION_SENSOR_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
#endif /* PROJECT_CONF_H_ */
|
#endif /* PROJECT_CONF_H_ */
|
||||||
|
|
||||||
|
|
|
@ -46,7 +46,6 @@
|
||||||
#include "dev/adc.h"
|
#include "dev/adc.h"
|
||||||
#include "dev/leds.h"
|
#include "dev/leds.h"
|
||||||
#include "dev/sys-ctrl.h"
|
#include "dev/sys-ctrl.h"
|
||||||
#include "dev/scb.h"
|
|
||||||
#include "dev/nvic.h"
|
#include "dev/nvic.h"
|
||||||
#include "dev/uart.h"
|
#include "dev/uart.h"
|
||||||
#include "dev/watchdog.h"
|
#include "dev/watchdog.h"
|
||||||
|
|
|
@ -141,27 +141,27 @@
|
||||||
/** BUTTON_SELECT -> PA3 */
|
/** BUTTON_SELECT -> PA3 */
|
||||||
#define BUTTON_SELECT_PORT GPIO_A_NUM
|
#define BUTTON_SELECT_PORT GPIO_A_NUM
|
||||||
#define BUTTON_SELECT_PIN 3
|
#define BUTTON_SELECT_PIN 3
|
||||||
#define BUTTON_SELECT_VECTOR NVIC_INT_GPIO_PORT_A
|
#define BUTTON_SELECT_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
/** BUTTON_LEFT -> PC4 */
|
/** BUTTON_LEFT -> PC4 */
|
||||||
#define BUTTON_LEFT_PORT GPIO_C_NUM
|
#define BUTTON_LEFT_PORT GPIO_C_NUM
|
||||||
#define BUTTON_LEFT_PIN 4
|
#define BUTTON_LEFT_PIN 4
|
||||||
#define BUTTON_LEFT_VECTOR NVIC_INT_GPIO_PORT_C
|
#define BUTTON_LEFT_VECTOR GPIO_C_IRQn
|
||||||
|
|
||||||
/** BUTTON_RIGHT -> PC5 */
|
/** BUTTON_RIGHT -> PC5 */
|
||||||
#define BUTTON_RIGHT_PORT GPIO_C_NUM
|
#define BUTTON_RIGHT_PORT GPIO_C_NUM
|
||||||
#define BUTTON_RIGHT_PIN 5
|
#define BUTTON_RIGHT_PIN 5
|
||||||
#define BUTTON_RIGHT_VECTOR NVIC_INT_GPIO_PORT_C
|
#define BUTTON_RIGHT_VECTOR GPIO_C_IRQn
|
||||||
|
|
||||||
/** BUTTON_UP -> PC6 */
|
/** BUTTON_UP -> PC6 */
|
||||||
#define BUTTON_UP_PORT GPIO_C_NUM
|
#define BUTTON_UP_PORT GPIO_C_NUM
|
||||||
#define BUTTON_UP_PIN 6
|
#define BUTTON_UP_PIN 6
|
||||||
#define BUTTON_UP_VECTOR NVIC_INT_GPIO_PORT_C
|
#define BUTTON_UP_VECTOR GPIO_C_IRQn
|
||||||
|
|
||||||
/** BUTTON_DOWN -> PC7 */
|
/** BUTTON_DOWN -> PC7 */
|
||||||
#define BUTTON_DOWN_PORT GPIO_C_NUM
|
#define BUTTON_DOWN_PORT GPIO_C_NUM
|
||||||
#define BUTTON_DOWN_PIN 7
|
#define BUTTON_DOWN_PIN 7
|
||||||
#define BUTTON_DOWN_VECTOR NVIC_INT_GPIO_PORT_C
|
#define BUTTON_DOWN_VECTOR GPIO_C_IRQn
|
||||||
|
|
||||||
/* Notify various examples that we have Buttons */
|
/* Notify various examples that we have Buttons */
|
||||||
#define PLATFORM_HAS_BUTTON 1
|
#define PLATFORM_HAS_BUTTON 1
|
||||||
|
|
|
@ -135,7 +135,7 @@ config_select(int type, int value)
|
||||||
|
|
||||||
ioc_set_over(BUTTON_SELECT_PORT, BUTTON_SELECT_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(BUTTON_SELECT_PORT, BUTTON_SELECT_PIN, IOC_OVERRIDE_PUE);
|
||||||
|
|
||||||
nvic_interrupt_enable(BUTTON_SELECT_VECTOR);
|
NVIC_EnableIRQ(BUTTON_SELECT_VECTOR);
|
||||||
|
|
||||||
gpio_register_callback(btn_callback, BUTTON_SELECT_PORT, BUTTON_SELECT_PIN);
|
gpio_register_callback(btn_callback, BUTTON_SELECT_PORT, BUTTON_SELECT_PIN);
|
||||||
return 1;
|
return 1;
|
||||||
|
@ -159,7 +159,7 @@ config_left(int type, int value)
|
||||||
|
|
||||||
ioc_set_over(BUTTON_LEFT_PORT, BUTTON_LEFT_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(BUTTON_LEFT_PORT, BUTTON_LEFT_PIN, IOC_OVERRIDE_PUE);
|
||||||
|
|
||||||
nvic_interrupt_enable(BUTTON_LEFT_VECTOR);
|
NVIC_EnableIRQ(BUTTON_LEFT_VECTOR);
|
||||||
|
|
||||||
gpio_register_callback(btn_callback, BUTTON_LEFT_PORT, BUTTON_LEFT_PIN);
|
gpio_register_callback(btn_callback, BUTTON_LEFT_PORT, BUTTON_LEFT_PIN);
|
||||||
return 1;
|
return 1;
|
||||||
|
@ -183,7 +183,7 @@ config_right(int type, int value)
|
||||||
|
|
||||||
ioc_set_over(BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN, IOC_OVERRIDE_PUE);
|
||||||
|
|
||||||
nvic_interrupt_enable(BUTTON_RIGHT_VECTOR);
|
NVIC_EnableIRQ(BUTTON_RIGHT_VECTOR);
|
||||||
|
|
||||||
gpio_register_callback(btn_callback, BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN);
|
gpio_register_callback(btn_callback, BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN);
|
||||||
return 1;
|
return 1;
|
||||||
|
@ -207,7 +207,7 @@ config_up(int type, int value)
|
||||||
|
|
||||||
ioc_set_over(BUTTON_UP_PORT, BUTTON_UP_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(BUTTON_UP_PORT, BUTTON_UP_PIN, IOC_OVERRIDE_PUE);
|
||||||
|
|
||||||
nvic_interrupt_enable(BUTTON_UP_VECTOR);
|
NVIC_EnableIRQ(BUTTON_UP_VECTOR);
|
||||||
|
|
||||||
gpio_register_callback(btn_callback, BUTTON_UP_PORT, BUTTON_UP_PIN);
|
gpio_register_callback(btn_callback, BUTTON_UP_PORT, BUTTON_UP_PIN);
|
||||||
return 1;
|
return 1;
|
||||||
|
@ -231,7 +231,7 @@ config_down(int type, int value)
|
||||||
|
|
||||||
ioc_set_over(BUTTON_DOWN_PORT, BUTTON_DOWN_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(BUTTON_DOWN_PORT, BUTTON_DOWN_PIN, IOC_OVERRIDE_PUE);
|
||||||
|
|
||||||
nvic_interrupt_enable(BUTTON_DOWN_VECTOR);
|
NVIC_EnableIRQ(BUTTON_DOWN_VECTOR);
|
||||||
|
|
||||||
gpio_register_callback(btn_callback, BUTTON_DOWN_PORT, BUTTON_DOWN_PIN);
|
gpio_register_callback(btn_callback, BUTTON_DOWN_PORT, BUTTON_DOWN_PIN);
|
||||||
return 1;
|
return 1;
|
||||||
|
|
|
@ -125,7 +125,7 @@
|
||||||
/** BUTTON_USER -> PC3 */
|
/** BUTTON_USER -> PC3 */
|
||||||
#define BUTTON_USER_PORT GPIO_C_NUM
|
#define BUTTON_USER_PORT GPIO_C_NUM
|
||||||
#define BUTTON_USER_PIN 3
|
#define BUTTON_USER_PIN 3
|
||||||
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_C
|
#define BUTTON_USER_VECTOR GPIO_C_IRQn
|
||||||
/* Notify various examples that we have Buttons */
|
/* Notify various examples that we have Buttons */
|
||||||
#define PLATFORM_HAS_BUTTON 1
|
#define PLATFORM_HAS_BUTTON 1
|
||||||
/** @} */
|
/** @} */
|
||||||
|
|
|
@ -48,7 +48,6 @@
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "dev/leds.h"
|
#include "dev/leds.h"
|
||||||
#include "dev/sys-ctrl.h"
|
#include "dev/sys-ctrl.h"
|
||||||
#include "dev/scb.h"
|
|
||||||
#include "dev/nvic.h"
|
#include "dev/nvic.h"
|
||||||
#include "dev/uart.h"
|
#include "dev/uart.h"
|
||||||
#include "dev/i2c.h"
|
#include "dev/i2c.h"
|
||||||
|
|
|
@ -158,10 +158,10 @@ config_user(int type, int value)
|
||||||
case SENSORS_ACTIVE:
|
case SENSORS_ACTIVE:
|
||||||
if(value) {
|
if(value) {
|
||||||
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
||||||
nvic_interrupt_enable(BUTTON_USER_VECTOR);
|
NVIC_EnableIRQ(BUTTON_USER_VECTOR);
|
||||||
} else {
|
} else {
|
||||||
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
||||||
nvic_interrupt_disable(BUTTON_USER_VECTOR);
|
NVIC_DisableIRQ(BUTTON_USER_VECTOR);
|
||||||
}
|
}
|
||||||
return value;
|
return value;
|
||||||
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:
|
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:
|
||||||
|
|
|
@ -47,7 +47,6 @@
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "dev/leds.h"
|
#include "dev/leds.h"
|
||||||
#include "dev/sys-ctrl.h"
|
#include "dev/sys-ctrl.h"
|
||||||
#include "dev/scb.h"
|
|
||||||
#include "dev/nvic.h"
|
#include "dev/nvic.h"
|
||||||
#include "dev/uart.h"
|
#include "dev/uart.h"
|
||||||
#include "dev/watchdog.h"
|
#include "dev/watchdog.h"
|
||||||
|
|
|
@ -137,7 +137,7 @@ configure(int type, int value)
|
||||||
/* Enable interrupts */
|
/* Enable interrupts */
|
||||||
GPIO_ENABLE_INTERRUPT(DIMMER_SYNC_PORT_BASE, DIMMER_SYNC_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(DIMMER_SYNC_PORT_BASE, DIMMER_SYNC_PIN_MASK);
|
||||||
// ioc_set_over(DIMMER_SYNC_PORT, DIMMER_SYNC_PIN, IOC_OVERRIDE_PUE);
|
// ioc_set_over(DIMMER_SYNC_PORT, DIMMER_SYNC_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(DIMMER_INT_VECTOR);
|
NVIC_EnableIRQ(DIMMER_INT_VECTOR);
|
||||||
|
|
||||||
enabled = 1;
|
enabled = 1;
|
||||||
dimming = DIMMER_DEFAULT_START_VALUE;
|
dimming = DIMMER_DEFAULT_START_VALUE;
|
||||||
|
|
|
@ -73,7 +73,7 @@
|
||||||
#ifdef DIMMER_CONF_INT_VECTOR
|
#ifdef DIMMER_CONF_INT_VECTOR
|
||||||
#define DIMMER_INT_VECTOR DIMMER_CONF_INT_VECTOR
|
#define DIMMER_INT_VECTOR DIMMER_CONF_INT_VECTOR
|
||||||
#else
|
#else
|
||||||
#define DIMMER_INT_VECTOR NVIC_INT_GPIO_PORT_A
|
#define DIMMER_INT_VECTOR GPIO_A_IRQn
|
||||||
#endif
|
#endif
|
||||||
/** @} */
|
/** @} */
|
||||||
/* -------------------------------------------------------------------------- */
|
/* -------------------------------------------------------------------------- */
|
||||||
|
|
|
@ -157,10 +157,10 @@ config_user(int type, int value)
|
||||||
case SENSORS_ACTIVE:
|
case SENSORS_ACTIVE:
|
||||||
if(value) {
|
if(value) {
|
||||||
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
||||||
nvic_interrupt_enable(BUTTON_USER_VECTOR);
|
NVIC_EnableIRQ(BUTTON_USER_VECTOR);
|
||||||
} else {
|
} else {
|
||||||
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
|
||||||
nvic_interrupt_disable(BUTTON_USER_VECTOR);
|
NVIC_DisableIRQ(BUTTON_USER_VECTOR);
|
||||||
}
|
}
|
||||||
return value;
|
return value;
|
||||||
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:
|
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:
|
||||||
|
|
|
@ -183,7 +183,7 @@ cc1200_arch_gpio0_setup_irq(int rising)
|
||||||
|
|
||||||
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
|
||||||
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
|
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
|
||||||
gpio_register_callback(cc1200_int_handler, CC1200_GDO0_PORT,
|
gpio_register_callback(cc1200_int_handler, CC1200_GDO0_PORT,
|
||||||
CC1200_GDO0_PIN);
|
CC1200_GDO0_PIN);
|
||||||
}
|
}
|
||||||
|
@ -205,7 +205,7 @@ cc1200_arch_gpio2_setup_irq(int rising)
|
||||||
|
|
||||||
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
|
||||||
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
|
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
|
||||||
gpio_register_callback(cc1200_int_handler, CC1200_GDO2_PORT,
|
gpio_register_callback(cc1200_int_handler, CC1200_GDO2_PORT,
|
||||||
CC1200_GDO2_PIN);
|
CC1200_GDO2_PIN);
|
||||||
}
|
}
|
||||||
|
@ -215,7 +215,7 @@ cc1200_arch_gpio0_enable_irq(void)
|
||||||
{
|
{
|
||||||
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
|
||||||
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
|
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
@ -229,7 +229,7 @@ cc1200_arch_gpio2_enable_irq(void)
|
||||||
{
|
{
|
||||||
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
|
||||||
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
|
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
void
|
void
|
||||||
|
|
|
@ -603,7 +603,7 @@ configure(int type, int value)
|
||||||
int_en = 1;
|
int_en = 1;
|
||||||
GPIO_ENABLE_INTERRUPT(GROVE_GYRO_INT_PORT_BASE, GROVE_GYRO_INT_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(GROVE_GYRO_INT_PORT_BASE, GROVE_GYRO_INT_PIN_MASK);
|
||||||
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(I2C_INT_VECTOR);
|
NVIC_EnableIRQ(I2C_INT_VECTOR);
|
||||||
|
|
||||||
PRINTF("Gyro: Data interrupt configured\n");
|
PRINTF("Gyro: Data interrupt configured\n");
|
||||||
return GROVE_GYRO_SUCCESS;
|
return GROVE_GYRO_SUCCESS;
|
||||||
|
|
|
@ -119,7 +119,7 @@ configure(int type, int value)
|
||||||
process_start(&motion_int_process, NULL);
|
process_start(&motion_int_process, NULL);
|
||||||
|
|
||||||
GPIO_ENABLE_INTERRUPT(MOTION_SENSOR_PORT_BASE, MOTION_SENSOR_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(MOTION_SENSOR_PORT_BASE, MOTION_SENSOR_PIN_MASK);
|
||||||
nvic_interrupt_enable(MOTION_SENSOR_VECTOR);
|
NVIC_EnableIRQ(MOTION_SENSOR_VECTOR);
|
||||||
return MOTION_SUCCESS;
|
return MOTION_SUCCESS;
|
||||||
}
|
}
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
|
|
|
@ -523,7 +523,7 @@ rtcc_set_alarm_time_date(simple_td_map *data, uint8_t state, uint8_t repeat,
|
||||||
} else {
|
} else {
|
||||||
GPIO_ENABLE_INTERRUPT(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
|
||||||
ioc_set_over(RTC_INT1_PORT, RTC_INT1_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(RTC_INT1_PORT, RTC_INT1_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(RTC_INT1_VECTOR);
|
NVIC_EnableIRQ(RTC_INT1_VECTOR);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (trigger == RTCC_TRIGGER_INT1) {
|
if (trigger == RTCC_TRIGGER_INT1) {
|
||||||
|
|
|
@ -453,7 +453,7 @@ configure(int type, int value)
|
||||||
* resistor instead if no external pull-up is present.
|
* resistor instead if no external pull-up is present.
|
||||||
*/
|
*/
|
||||||
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
|
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
|
||||||
nvic_interrupt_enable(I2C_INT_VECTOR);
|
NVIC_EnableIRQ(I2C_INT_VECTOR);
|
||||||
|
|
||||||
PRINTF("TSL256X: Interrupt configured\n");
|
PRINTF("TSL256X: Interrupt configured\n");
|
||||||
return TSL256X_SUCCESS;
|
return TSL256X_SUCCESS;
|
||||||
|
|
|
@ -449,8 +449,8 @@ configure(int type, int value)
|
||||||
|
|
||||||
GPIO_ENABLE_INTERRUPT(ANEMOMETER_SENSOR_PORT_BASE, ANEMOMETER_SENSOR_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(ANEMOMETER_SENSOR_PORT_BASE, ANEMOMETER_SENSOR_PIN_MASK);
|
||||||
GPIO_ENABLE_INTERRUPT(RAIN_GAUGE_SENSOR_PORT_BASE, RAIN_GAUGE_SENSOR_PIN_MASK);
|
GPIO_ENABLE_INTERRUPT(RAIN_GAUGE_SENSOR_PORT_BASE, RAIN_GAUGE_SENSOR_PIN_MASK);
|
||||||
nvic_interrupt_enable(ANEMOMETER_SENSOR_VECTOR);
|
NVIC_EnableIRQ(ANEMOMETER_SENSOR_VECTOR);
|
||||||
nvic_interrupt_enable(RAIN_GAUGE_SENSOR_VECTOR);
|
NVIC_EnableIRQ(RAIN_GAUGE_SENSOR_VECTOR);
|
||||||
|
|
||||||
enabled = 1;
|
enabled = 1;
|
||||||
PRINTF("Weather: started\n");
|
PRINTF("Weather: started\n");
|
||||||
|
|
|
@ -118,7 +118,7 @@ extern void (*rain_gauge_int_callback)(uint16_t value);
|
||||||
#ifdef WEATHER_METER_CONF_ANEMOMETER_VECTOR
|
#ifdef WEATHER_METER_CONF_ANEMOMETER_VECTOR
|
||||||
#define ANEMOMETER_SENSOR_VECTOR WEATHER_METER_CONF_ANEMOMETER_VECTOR
|
#define ANEMOMETER_SENSOR_VECTOR WEATHER_METER_CONF_ANEMOMETER_VECTOR
|
||||||
#else
|
#else
|
||||||
#define ANEMOMETER_SENSOR_VECTOR NVIC_INT_GPIO_PORT_D
|
#define ANEMOMETER_SENSOR_VECTOR GPIO_D_IRQn
|
||||||
#endif
|
#endif
|
||||||
/** @} */
|
/** @} */
|
||||||
/* -------------------------------------------------------------------------- */
|
/* -------------------------------------------------------------------------- */
|
||||||
|
@ -139,7 +139,7 @@ extern void (*rain_gauge_int_callback)(uint16_t value);
|
||||||
#ifdef WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
|
#ifdef WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
|
||||||
#define RAIN_GAUGE_SENSOR_VECTOR WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
|
#define RAIN_GAUGE_SENSOR_VECTOR WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
|
||||||
#else
|
#else
|
||||||
#define RAIN_GAUGE_SENSOR_VECTOR NVIC_INT_GPIO_PORT_D
|
#define RAIN_GAUGE_SENSOR_VECTOR GPIO_D_IRQn
|
||||||
#endif
|
#endif
|
||||||
/** @} */
|
/** @} */
|
||||||
/* -------------------------------------------------------------------------- */
|
/* -------------------------------------------------------------------------- */
|
||||||
|
|
|
@ -265,7 +265,7 @@
|
||||||
/** BUTTON_USER -> PA3 */
|
/** BUTTON_USER -> PA3 */
|
||||||
#define BUTTON_USER_PORT GPIO_A_NUM
|
#define BUTTON_USER_PORT GPIO_A_NUM
|
||||||
#define BUTTON_USER_PIN 3
|
#define BUTTON_USER_PIN 3
|
||||||
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
|
#define BUTTON_USER_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
/* Notify various examples that we have an user button.
|
/* Notify various examples that we have an user button.
|
||||||
* If ADC6 channel is used, then disable the user button
|
* If ADC6 channel is used, then disable the user button
|
||||||
|
@ -330,7 +330,7 @@
|
||||||
#define I2C_SDA_PIN 2
|
#define I2C_SDA_PIN 2
|
||||||
#define I2C_INT_PORT GPIO_D_NUM
|
#define I2C_INT_PORT GPIO_D_NUM
|
||||||
#define I2C_INT_PIN 1
|
#define I2C_INT_PIN 1
|
||||||
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
|
#define I2C_INT_VECTOR GPIO_D_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -368,7 +368,7 @@
|
||||||
#define CC1200_GDO2_PIN 0
|
#define CC1200_GDO2_PIN 0
|
||||||
#define CC1200_RESET_PORT GPIO_C_NUM
|
#define CC1200_RESET_PORT GPIO_C_NUM
|
||||||
#define CC1200_RESET_PIN 7
|
#define CC1200_RESET_PIN 7
|
||||||
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
|
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -264,7 +264,7 @@
|
||||||
/** BUTTON_USER -> PA3 */
|
/** BUTTON_USER -> PA3 */
|
||||||
#define BUTTON_USER_PORT GPIO_A_NUM
|
#define BUTTON_USER_PORT GPIO_A_NUM
|
||||||
#define BUTTON_USER_PIN 3
|
#define BUTTON_USER_PIN 3
|
||||||
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
|
#define BUTTON_USER_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
/* Notify various examples that we have an user button.
|
/* Notify various examples that we have an user button.
|
||||||
* If ADC6 channel is used, then disable the user button
|
* If ADC6 channel is used, then disable the user button
|
||||||
|
@ -329,7 +329,7 @@
|
||||||
#define I2C_SDA_PIN 2
|
#define I2C_SDA_PIN 2
|
||||||
#define I2C_INT_PORT GPIO_D_NUM
|
#define I2C_INT_PORT GPIO_D_NUM
|
||||||
#define I2C_INT_PIN 1
|
#define I2C_INT_PIN 1
|
||||||
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
|
#define I2C_INT_VECTOR GPIO_D_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -367,7 +367,7 @@
|
||||||
#define CC1200_GDO2_PIN 0
|
#define CC1200_GDO2_PIN 0
|
||||||
#define CC1200_RESET_PORT GPIO_C_NUM
|
#define CC1200_RESET_PORT GPIO_C_NUM
|
||||||
#define CC1200_RESET_PIN 7
|
#define CC1200_RESET_PIN 7
|
||||||
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
|
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -268,7 +268,7 @@
|
||||||
/** BUTTON_USER -> PA3 */
|
/** BUTTON_USER -> PA3 */
|
||||||
#define BUTTON_USER_PORT GPIO_A_NUM
|
#define BUTTON_USER_PORT GPIO_A_NUM
|
||||||
#define BUTTON_USER_PIN 3
|
#define BUTTON_USER_PIN 3
|
||||||
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
|
#define BUTTON_USER_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
/* Notify various examples that we have an user button.
|
/* Notify various examples that we have an user button.
|
||||||
* If ADC6 channel is used, then disable the user button
|
* If ADC6 channel is used, then disable the user button
|
||||||
|
@ -336,7 +336,7 @@
|
||||||
#define I2C_SDA_PIN 2
|
#define I2C_SDA_PIN 2
|
||||||
#define I2C_INT_PORT GPIO_D_NUM
|
#define I2C_INT_PORT GPIO_D_NUM
|
||||||
#define I2C_INT_PIN 1
|
#define I2C_INT_PIN 1
|
||||||
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
|
#define I2C_INT_VECTOR GPIO_D_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -395,7 +395,7 @@
|
||||||
#define CC1200_GDO2_PIN 0
|
#define CC1200_GDO2_PIN 0
|
||||||
#define CC1200_RESET_PORT GPIO_C_NUM
|
#define CC1200_RESET_PORT GPIO_C_NUM
|
||||||
#define CC1200_RESET_PIN 7
|
#define CC1200_RESET_PIN 7
|
||||||
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
|
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -460,7 +460,7 @@
|
||||||
#define RTC_SCL_PIN I2C_SCL_PIN
|
#define RTC_SCL_PIN I2C_SCL_PIN
|
||||||
#define RTC_INT1_PORT GPIO_A_NUM
|
#define RTC_INT1_PORT GPIO_A_NUM
|
||||||
#define RTC_INT1_PIN 4
|
#define RTC_INT1_PIN 4
|
||||||
#define RTC_INT1_VECTOR NVIC_INT_GPIO_PORT_A
|
#define RTC_INT1_VECTOR GPIO_A_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -293,7 +293,7 @@
|
||||||
*/
|
*/
|
||||||
#define BUTTON_USER_PORT GPIO_A_NUM
|
#define BUTTON_USER_PORT GPIO_A_NUM
|
||||||
#define BUTTON_USER_PIN 3
|
#define BUTTON_USER_PIN 3
|
||||||
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
|
#define BUTTON_USER_VECTOR GPIO_A_IRQn
|
||||||
|
|
||||||
/* Notify various examples that we have an user button.
|
/* Notify various examples that we have an user button.
|
||||||
* If ADC6 channel is used, then disable the user button
|
* If ADC6 channel is used, then disable the user button
|
||||||
|
@ -360,7 +360,7 @@
|
||||||
#define I2C_SDA_PIN 2
|
#define I2C_SDA_PIN 2
|
||||||
#define I2C_INT_PORT GPIO_D_NUM
|
#define I2C_INT_PORT GPIO_D_NUM
|
||||||
#define I2C_INT_PIN 0
|
#define I2C_INT_PIN 0
|
||||||
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
|
#define I2C_INT_VECTOR GPIO_D_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -419,7 +419,7 @@
|
||||||
#define CC1200_GDO2_PIN 0
|
#define CC1200_GDO2_PIN 0
|
||||||
#define CC1200_RESET_PORT GPIO_C_NUM
|
#define CC1200_RESET_PORT GPIO_C_NUM
|
||||||
#define CC1200_RESET_PIN 7
|
#define CC1200_RESET_PIN 7
|
||||||
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
|
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
@ -487,7 +487,7 @@
|
||||||
#define RTC_SCL_PIN I2C_SCL_PIN
|
#define RTC_SCL_PIN I2C_SCL_PIN
|
||||||
#define RTC_INT1_PORT GPIO_D_NUM
|
#define RTC_INT1_PORT GPIO_D_NUM
|
||||||
#define RTC_INT1_PIN 3
|
#define RTC_INT1_PIN 3
|
||||||
#define RTC_INT1_VECTOR NVIC_INT_GPIO_PORT_D
|
#define RTC_INT1_VECTOR GPIO_D_IRQn
|
||||||
/** @} */
|
/** @} */
|
||||||
/*---------------------------------------------------------------------------*/
|
/*---------------------------------------------------------------------------*/
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in a new issue